diff --git a/trlo/3rdparty/libspconv/include/spconv/check.hpp b/trlo/3rdparty/libspconv/include/spconv/check.hpp new file mode 100644 index 0000000..075e8aa --- /dev/null +++ b/trlo/3rdparty/libspconv/include/spconv/check.hpp @@ -0,0 +1,101 @@ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef __SPCONV_CHECK_HPP__ +#define __SPCONV_CHECK_HPP__ + +#include +#include +#include +#include + +#include + +namespace spconv { + +#if DEBUG +#define checkRuntime(call) spconv::check_runtime(call, #call, __LINE__, __FILE__) +#define checkKernel(...) \ + [&] { \ + __VA_ARGS__; \ + checkRuntime(cudaStreamSynchronize(nullptr)); \ + return spconv::check_runtime(cudaGetLastError(), #__VA_ARGS__, __LINE__, __FILE__); \ + }() +#define dprintf printf +#else +#define checkRuntime(call) spconv::check_runtime(call, #call, __LINE__, __FILE__) +#define checkKernel(...) \ + do { \ + __VA_ARGS__; \ + spconv::check_runtime(cudaPeekAtLastError(), #__VA_ARGS__, __LINE__, __FILE__); \ + } while (0) +#define dprintf(...) +#endif + +#define Assertf(cond, fmt, ...) \ + do { \ + if (!(cond)) { \ + fprintf(stderr, "Assert failed 💀. %s in file %s:%d, message: " fmt "\n", #cond, __FILE__, \ + __LINE__, __VA_ARGS__); \ + abort(); \ + } \ + } while (false) +#define Asserts(cond, s) \ + do { \ + if (!(cond)) { \ + fprintf(stderr, "Assert failed 💀. %s in file %s:%d, message: " s "\n", #cond, __FILE__, \ + __LINE__); \ + abort(); \ + } \ + } while (false) +#define Assert(cond) \ + do { \ + if (!(cond)) { \ + fprintf(stderr, "Assert failed 💀. %s in file %s:%d\n", #cond, __FILE__, __LINE__); \ + abort(); \ + } \ + } while (false) + +static inline std::string format(const char *fmt, ...) { + char buffer[2048]; + va_list vl; + va_start(vl, fmt); + vsnprintf(buffer, sizeof(buffer), fmt, vl); + return buffer; +} + +static inline bool check_runtime(cudaError_t e, const char *call, int line, const char *file) { + if (e != cudaSuccess) { + fprintf(stderr, + "CUDA Runtime error %s # %s, code = %s [ %d ] in file " + "%s:%d\n", + call, cudaGetErrorString(e), cudaGetErrorName(e), e, file, line); + abort(); + return false; + } + return true; +} + +}; // namespace spconv + +#endif // #ifndef __SPCONV_CHECK_HPP__ \ No newline at end of file diff --git a/trlo/3rdparty/libspconv/include/spconv/engine.hpp b/trlo/3rdparty/libspconv/include/spconv/engine.hpp new file mode 100644 index 0000000..8614b58 --- /dev/null +++ b/trlo/3rdparty/libspconv/include/spconv/engine.hpp @@ -0,0 +1,117 @@ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef __SPCONV_ENGINE_HPP__ +#define __SPCONV_ENGINE_HPP__ + +#include +#include +#include + +namespace spconv { + +#define Exported __attribute__((visibility("default"))) + +enum class DType : int { None = 0, Int32 = 1, Float16 = 2 }; +enum class Precision : int { None = 0, Float16 = 1, Int8 = 2 }; + +/** + Storage of data tensor +**/ +class DTensor { + public: + virtual std::vector features_shape() const = 0; + virtual DType features_dtype() const = 0; + virtual void* features_data() = 0; + + virtual std::vector indices_shape() const = 0; + virtual DType indices_dtype() const = 0; + virtual void* indices_data() = 0; + + virtual std::vector grid_size() const = 0; + virtual int device() const = 0; +}; + +/** + Engine types for sparse convolution +**/ +class Engine { + public: + /** + Inference function for sparse convolution + + features_shape: The shape of the input feature matrix, it must be two elements. + features_dtype: The data type of the input feature matrix, it must be Float16 now. + features_data: The data pointer of the input feature matrix + indices_shape: The shape of the input indices matrix, it must be two elements[n, 4] + indices_dtype: The data type of the input indices matrix, it must be Int32 now. + indices_data: The data pointer of the input indices matrix + batch: The batch size of the input, it must be 1 now. + grid_size: The grid size of the input data, For example: 41,1440,1440 or 1440,1440,41 + stream: Which stream is expected to enqueue the inference. + **/ + Exported virtual DTensor* forward(const std::vector& features_shape, + DType features_dtype, void* features_data, + const std::vector& indices_shape, DType indices_dtype, + void* indices_data, int batch, std::vector grid_size, + void* stream = nullptr) = 0; + + // If you change the precision of a node after loading the model, you should call this function to + // reconfigure it + Exported virtual void reconfigure() = 0; + + // If you want to execute an implicit PTQ calibration, you can enable int8calibration by marking + // it and collecting the maximum value of the tensor in the next forward. + Exported virtual void set_int8_calibration(bool enable) = 0; + + // You can modify the precision of a node with this function, but don't forget to call reconfigure + Exported virtual void set_node_precision_byname(const char* name, Precision compute_precision, + Precision output_precision) = 0; + Exported virtual void set_node_precision_byoptype(const char* optype, Precision compute_precision, + Precision output_precision) = 0; +}; + +/** + Create an engine and load the weights from onnx file + + onnx_file: Store the onnx of model structure, please use tool/deploy/export-scn.py to export the +corresponding onnx precision: What precision to use for model inference. For each layer's precision +should be stored in the "precision" attribute of the layer + - Model inference will ignore the "precision" attribute of each layer what if set to +Float16 +**/ +Exported std::shared_ptr load_engine_from_onnx(const std::string& onnx_file, + Precision precision = Precision::Float16); + +/** + Enable detailed information output + + enable: You should set this to true if you want to debug the model inference process. default: + false +*/ +Exported void set_verbose(bool enable); +Exported const char* get_precision_string(Precision precision); + +}; // namespace spconv + +#endif // #ifndef __SPCONV_ENGINE_HPP__ \ No newline at end of file diff --git a/trlo/3rdparty/libspconv/include/spconv/memory.hpp b/trlo/3rdparty/libspconv/include/spconv/memory.hpp new file mode 100644 index 0000000..915f6ce --- /dev/null +++ b/trlo/3rdparty/libspconv/include/spconv/memory.hpp @@ -0,0 +1,135 @@ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef __SPCONV_MEMORY_HPP__ +#define __SPCONV_MEMORY_HPP__ + +#include +#include +#include + +#include "check.hpp" + +namespace spconv { + +class GPUData { + public: + inline void *ptr() const { return ptr_; } + inline size_t bytes() const { return bytes_; } + inline bool empty() const { return ptr_ == nullptr; } + virtual ~GPUData() { free_memory(); } + GPUData() = default; + GPUData(const std::string &name) { this->name_ = name; } + + void alloc_or_resize_to(size_t nbytes) { + if (capacity_ < nbytes) { + dprintf("%s Free old %d, malloc new %d bytes.\n", name_.c_str(), capacity_, nbytes); + free_memory(); + checkRuntime(cudaMalloc(&ptr_, nbytes)); + capacity_ = nbytes; + } + bytes_ = nbytes; + } + + void alloc(size_t nbytes) { alloc_or_resize_to(nbytes); } + + void resize(size_t nbytes) { + if (capacity_ < nbytes) { + Assertf(false, "%s Failed to resize memory to %ld bytes. capacity = %ld", name_.c_str(), + nbytes, capacity_); + } + bytes_ = nbytes; + } + + void free_memory() { + if (ptr_) { + checkRuntime(cudaFree(ptr_)); + ptr_ = nullptr; + capacity_ = 0; + bytes_ = 0; + } + } + + private: + void *ptr_ = nullptr; + size_t bytes_ = 0; + size_t capacity_ = 0; + std::string name_; +}; + +template +class GPUMemory { + public: + T *ptr() const { return data_ ? (T *)data_->ptr() : nullptr; } + size_t size() const { return size_; } + size_t bytes() const { return data_ ? data_->bytes() : 0; } + bool empty() const { return data_ == nullptr || data_->empty(); } + bool unset() const { return data_ == nullptr; } + // GPUMemory() { data_.reset(new GPUData()); } + virtual ~GPUMemory() { data_.reset(); } + void set_gpudata(std::shared_ptr data) { this->data_ = data; } + + void alloc_or_resize_to(size_t size) { + if (data_) { + size_ = size; + data_->alloc_or_resize_to(size * sizeof(T)); + } else { + Asserts(false, "Failed to alloc or resize memory that because data is nullptr."); + } + } + + void alloc(size_t size) { alloc_or_resize_to(size); } + + void resize(size_t size) { + if (data_) { + size_ = size; + data_->resize(size * sizeof(T)); + } else { + Asserts(false, "Failed to resize memory that because data is nullptr."); + } + } + + private: + std::shared_ptr data_; + size_t size_ = 0; +}; + +class GPUDataManager { + public: + std::shared_ptr query_or_alloc(const std::string &tensor_id, + const std::string &subname = "default") { + std::shared_ptr &output = data_dict_[tensor_id][subname]; + if (output == nullptr) { + output.reset(new GPUData(tensor_id + "." + subname)); + } + return output; + } + + private: + std::unordered_map>> + data_dict_; +}; + +}; // namespace spconv + +#endif // #ifndef __SPCONV_MEMORY_HPP__ \ No newline at end of file diff --git a/trlo/3rdparty/libspconv/include/spconv/tensor.hpp b/trlo/3rdparty/libspconv/include/spconv/tensor.hpp new file mode 100644 index 0000000..50c92b0 --- /dev/null +++ b/trlo/3rdparty/libspconv/include/spconv/tensor.hpp @@ -0,0 +1,134 @@ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef __SPCONV_TENSOR_HPP__ +#define __SPCONV_TENSOR_HPP__ + +#include +#include +#include + +#include +#include +#include + +namespace spconv { + +#define Exported __attribute__((visibility("default"))) + +enum class DataType : int { + None = 0, + Int32 = 1, + Float16 = 2, + Float32 = 3, + Int64 = 4, + UInt64 = 5, + UInt32 = 6, + Int8 = 7, + UInt8 = 8 +}; + +struct TensorData { + void *data = nullptr; + DataType dtype = DataType::None; + size_t bytes = 0; + size_t capacity = 0; + bool device = true; + bool owner = false; + + bool empty() const { return data == nullptr; } + void reference(void *data, size_t bytes, DataType dtype, bool device); + void rearrange_and_realloc(size_t bytes, DataType dtype, bool device); + void free(); + virtual ~TensorData(); + + static TensorData *reference_new(void *data, size_t bytes, DataType dtype, bool device); + static TensorData *create(size_t bytes, DataType dtype, bool device); +}; + +struct Tensor { + std::vector shape; + std::shared_ptr data; + size_t numel = 0; + size_t ndim = 0; + + template + T *ptr() const { + return data ? (T *)data->data : nullptr; + } + void *ptr() const { return data ? data->data : nullptr; } + + template + T *begin() const { + return data ? (T *)data->data : nullptr; + } + template + T *end() const { + return data ? (T *)data->data + numel : nullptr; + } + + Exported int64_t size(int index) const { return shape[index]; } + Exported size_t bytes() const { return data ? data->bytes : 0; } + Exported bool empty() const { return data == nullptr || data->empty(); } + Exported DataType dtype() const { return data ? data->dtype : DataType::None; } + Exported bool device() const { return data ? data->device : false; } + Exported void reference(void *data, std::vector shape, DataType dtype, + bool device = true); + Exported void to_device_(void *stream = nullptr); + Exported void to_host_(void *stream = nullptr); + Exported Tensor to_device(void *stream = nullptr); + Exported Tensor to_host(void *stream = nullptr); + Exported Tensor clone(void *stream = nullptr); + Exported Tensor to_half(void *stream = nullptr); + Exported float absmax(void *stream = nullptr); + Exported void print(const std::string &prefix = "Tensor", size_t offset = 0, + size_t num_per_line = 10, size_t lines = 1) const; + Exported void memset(unsigned char value = 0, void *stream = nullptr); + Exported void arange(size_t num, void *stream = nullptr); + Exported bool save(const std::string &file, void *stream = nullptr) const; + Exported void create_(const std::vector &shape, DataType dtype, bool device = true); + + Exported Tensor() = default; + Exported Tensor(std::vector shape, DataType dtype, bool device = true); + + Exported static Tensor create(std::vector shape, DataType dtype, bool device = true); + Exported static Tensor from_data(void *data, std::vector shape, DataType dtype, + bool device = true, void *stream = nullptr); + Exported static Tensor from_data_reference(void *data, std::vector shape, DataType dtype, + bool device = true); + Exported static Tensor load(const std::string &file, bool device = true); + Exported static Tensor load_from_raw(const std::string &file, std::vector shape, + DataType dtype, bool device = true); + Exported static bool save(const Tensor &tensor, const std::string &file, void *stream = nullptr); +}; + +Exported std::vector toshape(const std::vector &ishape); +Exported float native_half2float(const unsigned short h); +Exported const char *dtype_string(DataType dtype); +Exported size_t dtype_bytes(DataType dtype); +template +Exported std::string format_shape(const std::vector<_T> &shape, bool space = true); + +}; // namespace spconv + +#endif // #ifndef __SPCONV_TENSOR_HPP__ \ No newline at end of file diff --git a/trlo/3rdparty/libspconv/include/spconv/timer.hpp b/trlo/3rdparty/libspconv/include/spconv/timer.hpp new file mode 100644 index 0000000..9a835a7 --- /dev/null +++ b/trlo/3rdparty/libspconv/include/spconv/timer.hpp @@ -0,0 +1,66 @@ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef __SPCONV_TIMER_HPP__ +#define __SPCONV_TIMER_HPP__ + +#include + +#include "check.hpp" + +namespace spconv { + +class EventTimer { + public: + EventTimer() { + checkRuntime(cudaEventCreate(&begin_)); + checkRuntime(cudaEventCreate(&end_)); + } + + virtual ~EventTimer() { + checkRuntime(cudaEventDestroy(begin_)); + checkRuntime(cudaEventDestroy(end_)); + } + + void start(void *stream) { + stream_ = (cudaStream_t)stream; + checkRuntime(cudaEventRecord(begin_, (cudaStream_t)stream)); + } + + float stop(const char *prefix, bool print = true) { + float times = 0; + checkRuntime(cudaEventRecord(end_, stream_)); + checkRuntime(cudaEventSynchronize(end_)); + checkRuntime(cudaEventElapsedTime(×, begin_, end_)); + if (print) printf("[Times %s]: %.3f ms\n", prefix, times); + return times; + } + + private: + cudaStream_t stream_ = nullptr; + cudaEvent_t begin_ = nullptr, end_ = nullptr; +}; + +}; // namespace spconv + +#endif // #ifndef __SPCONV_TIMER_HPP__ \ No newline at end of file diff --git a/trlo/3rdparty/libspconv/include/spconv/version.hpp b/trlo/3rdparty/libspconv/include/spconv/version.hpp new file mode 100644 index 0000000..12e64f7 --- /dev/null +++ b/trlo/3rdparty/libspconv/include/spconv/version.hpp @@ -0,0 +1,35 @@ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef __SPCONV_VERSION_HPP__ +#define __SPCONV_VERSION_HPP__ + +#define NVSPCONV_MAJOR 1 +#define NVSPCONV_MINOR 0 +#define NVSPCONV_REL 1 +#define NVSPCONV_STR(v) #v +#define NVSPCONV_VERSION_COMBIN(major, minor, rel) \ + (NVSPCONV_STR(major) "." NVSPCONV_STR(minor) "." NVSPCONV_STR(rel)) +#define NVSPCONV_VERSION NVSPCONV_VERSION_COMBIN(NVSPCONV_MAJOR, NVSPCONV_MINOR, NVSPCONV_REL) + +#endif // #ifndef __SPCONV_VERSION_HPP__ \ No newline at end of file diff --git a/trlo/3rdparty/libspconv/lib/aarch64/libspconv.so b/trlo/3rdparty/libspconv/lib/aarch64/libspconv.so new file mode 100644 index 0000000..bced83f Binary files /dev/null and b/trlo/3rdparty/libspconv/lib/aarch64/libspconv.so differ diff --git a/trlo/3rdparty/libspconv/lib/x86_64/libspconv.so b/trlo/3rdparty/libspconv/lib/x86_64/libspconv.so new file mode 100644 index 0000000..58929af Binary files /dev/null and b/trlo/3rdparty/libspconv/lib/x86_64/libspconv.so differ diff --git a/trlo/CMakeLists.txt b/trlo/CMakeLists.txt new file mode 100644 index 0000000..0530c88 --- /dev/null +++ b/trlo/CMakeLists.txt @@ -0,0 +1,176 @@ +############################################################# +# # +# Copyright (c) 2022, University of California, Los Angeles # +# # +# Authors: Kenny J. Chen, Brett T. Lopez # +# Contact: kennyjchen@ucla.edu, btlopez@ucla.edu # +# # +############################################################# + +cmake_minimum_required(VERSION 3.10.0) +project(trlo) +set(arch ${CMAKE_HOST_SYSTEM_PROCESSOR}) + +#add_compile_options(-std=c++14) +set(CMAKE_CXX_STANDARD 14) +set(CMAKE_BUILD_TYPE "Release") +set(CMAKE_CXX_FLAGS_RELEASE "-Wno-deprecated-declarations -O3 -g -pthread") +#set(CMAKE_CXX_FLAGS_RELEASE "-Wall -O3 -g -pthread") + +# PCL +find_package( PCL REQUIRED ) +include_directories(${PCL_INCLUDE_DIRS}) +add_definitions(${PCL_DEFINITIONS}) +link_directories(${PCL_LIBRARY_DIRS}) + +# Ceres +find_package(Ceres REQUIRED) +include_directories(${CERES_INCLUDE_DIRS}) +link_libraries(${CERES_LIBRARIES}) + +# OpenCV +find_package( OpenCV REQUIRED ) +include_directories( ${OpenCV_INCLUDE_DIRS} ) +link_libraries(${OpenCV_LIBRARIES}) + +# Eigen3 +find_package( Eigen3 REQUIRED ) +include_directories(${EIGEN3_INCLUDE_DIR}) + +# OpenMP +include(FindOpenMP) +if(OPENMP_FOUND) + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") + #set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}") +else(OPENMP_FOUND) + message("ERROR: OpenMP could not be found.") +endif(OPENMP_FOUND) + +set(CMAKE_THREAD_PREFER_PTHREAD TRUE) +set(THREADS_PREFER_PTHREAD_FLAG TRUE) +find_package(Threads REQUIRED) + +# CUDA +find_package(CUDA REQUIRED) + +set(CUDA_TOOLKIT_ROOT_DIR /usr/local/cuda-11.3) +set(CUDA_INCLUDE_DIRS ${CUDA_TOOLKIT_ROOT_DIR}/${CUDA_INSTALL_TARGET_DIR}/include) + +# TENSORRT install path +set(TENSORRT_ROOT /home/jyp/3rdparty/TensorRT-8.5.3.1) +set(TENSORRT_INCLUDE_DIRS ${TENSORRT_ROOT}/include/) +set(TENSORRT_LIBRARY_DIRS ${TENSORRT_ROOT}/lib) + +if(${CMAKE_BUILD_TYPE} STREQUAL "Debug") + message("Using Debug Mode") + set(CUDA_NVCC_FLAGS ${CUDA_NVCC_FLAGS} -g -G --ptxas-options=-v) +endif() + +include_directories( + ${CUDA_INCLUDE_DIRS} + ${TENSORRT_INCLUDE_DIRS} + 3rdparty/libspconv/include + include +) + +link_directories( + ${TENSORRT_LIBRARY_DIRS} + 3rdparty/libspconv/lib/${arch} + /usr/lib/aarch64-linux-gnu + /usr/aarch64-linux-gnu/lib/ +) + +find_package(catkin REQUIRED COMPONENTS + roscpp + std_msgs + sensor_msgs + geometry_msgs + pcl_ros + message_generation + jsk_recognition_msgs +) + + +add_service_files( + DIRECTORY srv + FILES + save_pcd.srv + save_traj.srv +) + +generate_messages() + +catkin_package( + CATKIN_DEPENDS + roscpp + std_msgs + sensor_msgs + geometry_msgs + pcl_ros + INCLUDE_DIRS + include + LIBRARIES + ${PROJECT_NAME} + nano_gicp + nanoflann +) + +include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_LIBRARIES}) + +set(CMAKE_TRY_COMPILE_TARGET_TYPE STATIC_LIBRARY) +file(WRITE ${CMAKE_BINARY_DIR}/test_cpuid.cpp "#include ") +try_compile(HAS_CPUID ${CMAKE_BINARY_DIR} ${CMAKE_BINARY_DIR}/test_cpuid.cpp) +file(REMOVE ${CMAKE_BINARY_DIR}/test_cpuid.cpp) +if(HAS_CPUID) + add_compile_definitions(HAS_CPUID) +endif() + +file(GLOB_RECURSE CENTER_POINTPILLARS_FILES + src/center_pointpillars/*.cu + src/center_pointpillars/*.cpp +) + +# 3D MOT +# set(3D_MOT_FILES src/3d_mot/3d_mot_node.cpp src/3d_mot/imm_ukf_jpda.cpp src/3d_mot/ukf.cpp ) +# add_executable(3d_mot_node ${3D_MOT_FILES}) +# target_link_libraries(3d_mot_node ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} ${PCL_LIBRARIES}) + +# Center_PointPillarss Node +set(3D_MOT_FILES src/3d_mot/imm_ukf_jpda.cpp src/3d_mot/ukf.cpp ) +cuda_add_executable(centerpp_node src/centerpp_node/centerpp_node.cpp ${CENTER_POINTPILLARS_FILES} ${3D_MOT_FILES}) +target_link_libraries(centerpp_node + libnvinfer.so + libnvonnxparser.so + libspconv.so + ${catkin_LIBRARIES} + ${PCL_LIBRARIES} +) + +# NanoFLANN +add_library(nanoflann STATIC + src/nano_gicp/nanoflann.cc +) +target_link_libraries(nanoflann ${PCL_LIBRARIES}) +target_include_directories(nanoflann PUBLIC include ${PCL_INCLUDE_DIRS}) + +# NanoGICP +add_library(nano_gicp STATIC + src/nano_gicp/lsq_registration.cc + src/nano_gicp/nano_gicp.cc +) +#target_link_libraries(nano_gicp ${PCL_LIBRARIES} ${OpenMP_LIBS} nanoflann) +target_link_libraries(nano_gicp ${PCL_LIBRARIES} OpenMP::OpenMP_CXX nanoflann) +target_include_directories(nano_gicp PUBLIC include ${PCL_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR}) + +# Odometry Node +add_executable(trlo_odom_node src/trlo/odom_node.cc src/trlo/odom.cc) +add_dependencies(trlo_odom_node ${catkin_EXPORTED_TARGETS}) +target_compile_options(trlo_odom_node PRIVATE ${OpenMP_FLAGS}) +target_link_libraries(trlo_odom_node ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenMP_LIBS} Threads::Threads nano_gicp) + +# Mapping Node +add_executable (trlo_map_node src/trlo/map_node.cc src/trlo/map.cc) +add_dependencies(trlo_map_node ${catkin_EXPORTED_TARGETS}) +target_compile_options(trlo_map_node PRIVATE ${OpenMP_FLAGS}) +target_link_libraries(trlo_map_node ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenMP_LIBS} Threads::Threads) diff --git a/trlo/cfg/center_pp.yaml b/trlo/cfg/center_pp.yaml new file mode 100644 index 0000000..8b8e20c --- /dev/null +++ b/trlo/cfg/center_pp.yaml @@ -0,0 +1,24 @@ +##################################################################################### +# # +# Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences # +# # +# Authors: Yanpeng Jia # +# Contact: jiayanpeng@sia.cn # +# # +##################################################################################### + +center_pp: + frame: + odom_frame: robot/odom + child_frame: robot/base_link + + preprocessing: + threshold: + MINIMUM_RANGE: 0.5 + MAXMUM_RANGE: 80 + cropBoxFilter: + use: true + size: 0.5 + voxelFilter: + use: true + res: 0.25 # 0.25 diff --git a/trlo/cfg/params.yaml b/trlo/cfg/params.yaml new file mode 100644 index 0000000..7270d67 --- /dev/null +++ b/trlo/cfg/params.yaml @@ -0,0 +1,77 @@ +##################################################################################### +# # +# Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences # +# # +# Authors: Yanpeng Jia # +# Contact: jiayanpeng@sia.cn # +# # +##################################################################################### + +trlo: + + odomNode: + + initialPose: + use: true + position: + x: 0.0 + y: 0.0 + z: 0.0 + orientation: + w: 1.0 + x: 0.0 + y: 0.0 + z: 0.0 + + preprocessing: + cropBoxFilter: + use: false + size: 1.0 + voxelFilter: + scan: + use: false + res: 0.25 + submap: + use: true + res: 0.5 + + keyframe: + threshD: 5.0 + threshR: 45.0 + + submap: + keyframe: + knn: 10 + kcv: 10 + kcc: 10 + + imu: + calibTime: 3 + bufferSize: 2000 + + box: + bufferSize: 3 + + groundL: + threshold: 0.2 + + gicp: + minNumPoints: 10 + s2s: + kCorrespondences: 10 + maxCorrespondenceDistance: 1.0 + maxIterations: 32 + transformationEpsilon: 0.01 + euclideanFitnessEpsilon: 0.01 + ransac: + iterations: 5 + outlierRejectionThresh: 1.0 + s2m: + kCorrespondences: 20 + maxCorrespondenceDistance: 0.5 + maxIterations: 32 + transformationEpsilon: 0.01 + euclideanFitnessEpsilon: 0.01 + ransac: + iterations: 5 + outlierRejectionThresh: 1.0 diff --git a/trlo/cfg/trlo.yaml b/trlo/cfg/trlo.yaml new file mode 100644 index 0000000..3d9ecff --- /dev/null +++ b/trlo/cfg/trlo.yaml @@ -0,0 +1,27 @@ +##################################################################################### +# # +# Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences # +# # +# Authors: Yanpeng Jia # +# Contact: jiayanpeng@sia.cn # +# # +##################################################################################### + +trlo: + + version: 1.0.0 + + adaptiveParams: true + + imu: false + gravityAlign: false + ground: true + + odomNode: + odom_frame: odom + child_frame: base_link + + mapNode: + publishFullMap: true + publishFreq: 1.0 + leafSize: 0.25 diff --git a/trlo/data/data.bin b/trlo/data/data.bin new file mode 100644 index 0000000..b5adb8d Binary files /dev/null and b/trlo/data/data.bin differ diff --git a/trlo/include/3d_mot/imm_ukf_jpda.h b/trlo/include/3d_mot/imm_ukf_jpda.h new file mode 100644 index 0000000..91f6082 --- /dev/null +++ b/trlo/include/3d_mot/imm_ukf_jpda.h @@ -0,0 +1,32 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +#ifndef MY_PCL_TUTORIAL_IMM_UKF_JPDAF_H +#define MY_PCL_TUTORIAL_IMM_UKF_JPDAF_H + +#include +#include +#include +#include + +using namespace std; +using namespace pcl; + +void getOriginPoints(Eigen::Matrix3f pose); + +Eigen::VectorXd getCpFromBbox(PointCloud bBox); + +void immUkfJpdaf(vector> bBoxes, double timestamp, + PointCloud& targets, vector>& targetVandYaw, + vector& trackManage, vector& isStaticVec, + vector& isVisVec, vector>& visBB); + + + + +#endif /* MY_PCL_TUTORIAL_IMM_UKF_JPDAF_H */ diff --git a/trlo/include/3d_mot/ukf.h b/trlo/include/3d_mot/ukf.h new file mode 100644 index 0000000..cdd37f1 --- /dev/null +++ b/trlo/include/3d_mot/ukf.h @@ -0,0 +1,264 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +#ifndef MY_PCL_TUTORIAL_UKF_H +#define MY_PCL_TUTORIAL_UKF_H +// #include "measurement_package.h" +#include "Eigen/Dense" +#include +#include +#include +#include +#include + + +using Eigen::MatrixXd; +using Eigen::VectorXd; + +class UKF { +public: + + ///* initially set to false, set to true in first call of ProcessMeasurement + bool is_initialized_; + + ///* if this is false, laser measurements will be ignored (except for init) + bool use_laser_; + + ///* if this is false, radar measurements will be ignored (except for init) + bool use_radar_; + +// ///* state vector: [pos1 pos2 vel_abs yaw_angle yaw_rate] in SI units and rad + MatrixXd x_merge_; + + ///* state vector: [pos1 pos2 vel_abs yaw_angle yaw_rate] in SI units and rad + MatrixXd x_cv_; + + ///* state vector: [pos1 pos2 vel_abs yaw_angle yaw_rate] in SI units and rad + MatrixXd x_ctrv_; + + ///* state vector: [pos1 pos2 vel_abs yaw_angle yaw_rate] in SI units and rad + MatrixXd x_rm_; + +// ///* state covariance matrix + MatrixXd P_merge_; + + ///* state covariance matrix + MatrixXd P_cv_; + + ///* state covariance matrix + MatrixXd P_ctrv_; + + ///* state covariance matrix + MatrixXd P_rm_; + + ///* predicted sigma points matrix + MatrixXd Xsig_pred_cv_; + + ///* predicted sigma points matrix + MatrixXd Xsig_pred_ctrv_; + + ///* predicted sigma points matrix + MatrixXd Xsig_pred_rm_; + + ///* time when the state is true, in us + long long time_us_; + + ///* Process noise standard deviation longitudinal acceleration in m/s^2 + double std_a_cv_; + double std_a_ctrv_; + double std_a_rm_; + ///* Process noise standard deviation yaw acceleration in rad/s^2 + // CTRV + double std_ctrv_yawdd_; + // CV + double std_cv_yawdd_; + + double std_rm_yawdd_; + + ///* Laser measurement noise standard deviation position1 in m + double std_laspx_; + + ///* Laser measurement noise standard deviation position2 in m + double std_laspy_; + + ///* Radar measurement noise standard deviation radius in m + double std_radr_; + + ///* Radar measurement noise standard deviation angle in rad + double std_radphi_; + + ///* Radar measurement noise standard deviation radius change in m/s + double std_radrd_ ; + + ///* Weights of sigma points + VectorXd weights_; + + ///* State dimension + int n_x_; + + ///* Augmented state dimension + int n_aug_; + + ///* Sigma point spreading parameter + double lambda_; + + ///* Augmented sigma point spreading parameter + double lambda_aug_; + + ///* the current NIS for radar + double NIS_radar_; + + ///* the current NIS for laser + double NIS_laser_; + + int count_; + int count_empty_; + + double modeMatchProbCV2CV_; + double modeMatchProbCTRV2CV_; + double modeMatchProbRM2CV_ ; + + double modeMatchProbCV2CTRV_; + double modeMatchProbCTRV2CTRV_ ; + double modeMatchProbRM2CTRV_ ; + + double modeMatchProbCV2RM_ ; + double modeMatchProbCTRV2RM_ ; + double modeMatchProbRM2RM_ ; + + double modeMatchProbCV_; + + double modeMatchProbCTRV_; + + double modeMatchProbRM_; + + double modeProbCV_; + double modeProbCTRV_; + double modeProbRM_; + + std::vector ini_u_; + + std::vector p1_; + + std::vector p2_; + + std::vector p3_; + + VectorXd zPredCVr_; + VectorXd zPredCTRVr_; + VectorXd zPredRMr_; + + VectorXd zPredCVl_; + VectorXd zPredCTRVl_; + VectorXd zPredRMl_; + + MatrixXd lS_cv_; + MatrixXd lS_ctrv_; + MatrixXd lS_rm_; + MatrixXd rS_cv_; + MatrixXd rS_ctrv_; + MatrixXd rS_rm_; + + MatrixXd K_cv_; + MatrixXd K_ctrv_; + MatrixXd K_rm_; + + double gammaG_; + double pD_; + double pG_; + + int lifetime_; + std::vector velo_history_; + bool isStatic_; + + // bounding box params + bool isVisBB_; + // todo: need initialization? + pcl::PointCloud BBox_; + pcl::PointCloud bestBBox_; + double bestYaw_; + double bb_yaw_; + double bb_area_; + std::vector bb_yaw_history_; + std::vector bb_vel_history_; + std::vector bb_area_history_; + + // for env classification + VectorXd initMeas_; + double distFromInit_; + + + std::vector local2local_; + std::vector local2localYawVec_; + + double x_merge_yaw_; + + /** + * Constructor + */ + UKF(); + + /** + * Destructor + */ + virtual ~UKF(); + + void UpdateYawWithHighProb(); + + void Initialize(VectorXd z, double timestamp); + + double CalculateGauss(VectorXd z, int sensorInd, int modelInd); + + void UpdateModeProb(std::vector lambdaVec); + + void MergeEstimationAndCovariance(); + + void MixingProbability(); + + void Interaction(); + + void MeasurementValidation(VectorXd z, std::vector& meas); + + void PDAupdate(std::vector z, int modelInd); + + /** + * ProcessMeasurement + * @param meas_package The latest measurement data of either radar or laser + */ + void ProcessIMMUKF(double dt); + + void PostProcessIMMUKF(std::vector lambdaVec); + + + void Ctrv(double p_x, double p_y, double v, double yaw, double yawd, double nu_a, double nu_yawdd, double delta_t, std::vector&state); + + void Cv(double p_x, double p_y, double v, double yaw, double yawd, double nu_a, double nu_yawdd, double delta_t, std::vector&state); + + void randomMotion(double p_x, double p_y, double v, double yaw, double yawd, double nu_a, double nu_yawdd, double delta_t, std::vector&state); + + /** + * Prediction Predicts sigma points, the state, and the state covariance + * matrix + * @param delta_t Time between k and k+1 in s + */ + void Prediction(double delta_t, int modelInd); + + /** + * Updates the state and the state covariance matrix using a laser measurement + * @param meas_package The measurement at k+1 + */ + void UpdateLidar(int modelInd); + + /** + * Updates the state and the state covariance matrix using a radar measurement + * @param meas_package The measurement at k+1 + */ + // void UpdateRadar(MeasurementPackage meas_package, int modelInd); +}; + +#endif /* UKF_H */ diff --git a/trlo/include/center_pointpillars/centerpoint.h b/trlo/include/center_pointpillars/centerpoint.h new file mode 100644 index 0000000..2cb2b04 --- /dev/null +++ b/trlo/include/center_pointpillars/centerpoint.h @@ -0,0 +1,99 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#include + +#include "center_pointpillars/common.h" +#include "NvInfer.h" +#include "NvOnnxConfig.h" +#include "NvInferRuntime.h" +#include "center_pointpillars/preprocess.h" +#include "center_pointpillars/postprocess.h" +#include "spconv/engine.hpp" +#include "center_pointpillars/tensorrt.hpp" +#include "center_pointpillars/timer.hpp" + +typedef struct float11 { float val[11]; } float11; + +class CenterPoint { + private: + Params params_; + bool verbose_; + + std::shared_ptr pre_; + std::shared_ptr scn_engine_; + std::shared_ptr trt_; + std::shared_ptr post_; + + std::vector timing_pre_; + std::vector timing_scn_engine_; + std::vector timing_trt_; + std::vector timing_post_; + + unsigned int* h_detections_num_; + float* d_detections_; + float* d_detections_reshape_; //add d_detections_reshape_ + + half* d_reg_[NUM_TASKS]; + half* d_height_[NUM_TASKS]; + half* d_dim_[NUM_TASKS]; + half* d_rot_[NUM_TASKS]; + half* d_vel_[NUM_TASKS]; + half* d_hm_[NUM_TASKS]; + + int reg_n_; + int reg_c_; + int reg_h_; + int reg_w_; + int height_c_; + int dim_c_; + int rot_c_; + int vel_c_; + int hm_c_[NUM_TASKS]; + + half* d_voxel_features; + unsigned int* d_voxel_indices; + std::vector sparse_shape; + + std::vector detections_; + unsigned int h_mask_size_; + uint64_t* h_mask_ = nullptr; + EventTimer timer_; + + public: + CenterPoint(std::string modelFile_Dir, bool verbose = false); + ~CenterPoint(void); + + int prepare(); + int doinfer(void* points, unsigned int point_num, cudaStream_t stream); + std::vector nms_pred_; + void perf_report(); +}; \ No newline at end of file diff --git a/trlo/include/center_pointpillars/common.h b/trlo/include/center_pointpillars/common.h new file mode 100644 index 0000000..cbd751f --- /dev/null +++ b/trlo/include/center_pointpillars/common.h @@ -0,0 +1,107 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef COMMON_H_ +#define COMMON_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +const unsigned int MAX_DET_NUM = 1000; // nms_pre_max_size = 1000; +const unsigned int DET_CHANNEL = 11; +const unsigned int MAX_POINTS_NUM = 300000; +const unsigned int NUM_TASKS = 6; + +#define checkCudaErrors(op) \ + { \ + auto status = ((op)); \ + if (status != 0) { \ + std::cout << "Cuda failure: " << cudaGetErrorString(status) << " in file " << __FILE__ \ + << ":" << __LINE__ << " error status: " << status << std::endl; \ + abort(); \ + } \ + } + + +class Params +{ + public: + const unsigned int task_num_stride[NUM_TASKS] = { 0, 1, 3, 5, 6, 8, }; + static const unsigned int num_classes = 10; + const char *class_name[num_classes] = { "car", "truck", "construction_vehicle", "bus", "trailer", "barrier", "motorcycle", "bicycle", "pedestrian", "traffic_cone"}; + + const float out_size_factor = 8; + const float voxel_size[2] = { 0.075, 0.075, }; + const float pc_range[2] = { -54, -54, }; + const float score_threshold = 0.1; + const float post_center_range[6] = { -61.2, -61.2, -10.0, 61.2, 61.2, 10.0, }; + const float nms_iou_threshold = 0.2; + const unsigned int nms_pre_max_size = MAX_DET_NUM; + const unsigned int nms_post_max_size= 83; + + const float min_x_range = -54; + const float max_x_range = 54; + const float min_y_range = -54; + const float max_y_range = 54; + const float min_z_range = -5.0; + const float max_z_range = 3.0; + // the size of a pillar + const float pillar_x_size = 0.075; + const float pillar_y_size = 0.075; + const float pillar_z_size = 0.2; + const int max_points_per_voxel = 10; + + const unsigned int max_voxels = 160000; + const unsigned int feature_num = 5; + + Params() {}; + + int getGridXSize() { + return (int)std::round((max_x_range - min_x_range) / pillar_x_size); + } + int getGridYSize() { + return (int)std::round((max_y_range - min_y_range) / pillar_y_size); + } + int getGridZSize() { + return (int)std::round((max_z_range - min_z_range) / pillar_z_size); + } +}; + +#endif \ No newline at end of file diff --git a/trlo/include/center_pointpillars/kernel.h b/trlo/include/center_pointpillars/kernel.h new file mode 100644 index 0000000..0cb9dc3 --- /dev/null +++ b/trlo/include/center_pointpillars/kernel.h @@ -0,0 +1,95 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef _KERNEL_H_ +#define _KERNEL_H_ + +#include "common.h" + +const int NMS_THREADS_PER_BLOCK = sizeof(uint64_t) * 8; +const int THREADS_FOR_VOXEL = 256; + +#define DIVUP(x, y) (x + y - 1) / y + +cudaError_t voxelizationLaunch(const float *points, size_t points_size, + float min_x_range, float max_x_range, + float min_y_range, float max_y_range, + float min_z_range, float max_z_range, + float voxel_x_size, float voxel_y_size, float voxel_z_size, + int grid_y_size, int grid_x_size, int feature_num, + int max_voxels, int max_points_voxel, + unsigned int *hash_table, + unsigned int *num_points_per_voxel, float *voxel_features, + unsigned int *voxel_indices, unsigned int *real_voxel_num, + cudaStream_t stream = 0); + +cudaError_t featureExtractionLaunch(float *voxels_temp_, + unsigned int *num_points_per_voxel, + const unsigned int real_voxel_num, int max_points_per_voxel, + int feature_num, half *voxel_features, cudaStream_t stream_ = 0); + +int postprocess_launch( + int N, + int H, + int W, + int C_reg, + int C_height, + int C_dim, + int C_rot, + int C_vel, + int C_hm, + const half *reg, + const half *height, + const half *dim, + const half *rot, + const half *vel, + const half *hm, + unsigned int *detection_num, + float *detections, + const float *post_center_range, + float out_size_factor, + const float *voxel_size, + const float *pc_range, + float score_threshold, + cudaStream_t stream = 0); + +int nms_launch(unsigned int boxes_num, + float *boxes_sorted, + float nms_iou_threshold, + uint64_t* mask, + cudaStream_t stream = 0); + +int permute_launch(unsigned int boxes_num, + const float *boxes_sorted, + float * permute_boxes_sorted, + cudaStream_t stream); + +#endif \ No newline at end of file diff --git a/trlo/include/center_pointpillars/postprocess.h b/trlo/include/center_pointpillars/postprocess.h new file mode 100644 index 0000000..4585384 --- /dev/null +++ b/trlo/include/center_pointpillars/postprocess.h @@ -0,0 +1,101 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef POSTPROCESS_H_ +#define POSTPROCESS_H_ + +#include +#include "common.h" +#include "kernel.h" + +/* +box_encodings: (B, N, 7 + C) or (N, 7 + C) [x, y, z, dx, dy, dz, heading or *[cos, sin], ...] +anchors: (B, N, 7 + C) or (N, 7 + C) [x, y, z, dx, dy, dz, heading, ...] +*/ +struct Bndbox { + float x; + float y; + float z; + float w; + float l; + float h; + float vx; + float vy; + float rt; + int id; + float score; + Bndbox(){}; + Bndbox(float x_, float y_, float z_, float w_, float l_, float h_, float vx_, float vy_, float rt_, int id_, float score_) + : x(x_), y(y_), z(z_), w(w_), l(l_), h(h_), vx(vx_), vy(vy_), rt(rt_), id(id_), score(score_) {} +}; + +class PostProcessCuda { + private: + Params params_; + float* d_post_center_range_ = nullptr; + float* d_voxel_size_ = nullptr; + float* d_pc_range_ = nullptr; + + public: + PostProcessCuda(); + ~PostProcessCuda(); + + int doPostDecodeCuda( + int N, + int H, + int W, + int C_reg, + int C_height, + int C_dim, + int C_rot, + int C_vel, + int C_hm, + const half *reg, + const half *height, + const half *dim, + const half *rot, + const half *vel, + const half *hm, + unsigned int *detection_num, + float *detections, cudaStream_t stream); + + int doPostNMSCuda( + unsigned int boxes_num, + float *boxes_sorted, + uint64_t* mask, cudaStream_t stream); + + int doPermuteCuda( + unsigned int boxes_num, + const float *boxes_sorted, + float * permute_boxes, cudaStream_t stream); +}; + +#endif \ No newline at end of file diff --git a/trlo/include/center_pointpillars/preprocess.h b/trlo/include/center_pointpillars/preprocess.h new file mode 100644 index 0000000..b555137 --- /dev/null +++ b/trlo/include/center_pointpillars/preprocess.h @@ -0,0 +1,60 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#include "kernel.h" + +class PreProcessCuda { + private: + Params params_; + unsigned int *point2voxel_offset_; + unsigned int *hash_table_; + float *voxels_temp_; + + unsigned int *d_real_num_voxels_; + unsigned int *h_real_num_voxels_; + half *d_voxel_features_; + unsigned int *d_voxel_num_; + unsigned int *d_voxel_indices_; + + unsigned int hash_table_size_; + unsigned int voxels_temp_size_; + unsigned int voxel_features_size_; + unsigned int voxel_idxs_size_; + unsigned int voxel_num_size_; + + public: + PreProcessCuda(); + ~PreProcessCuda(); + + int alloc_resource(); + int generateVoxels(const float *points, size_t points_size, cudaStream_t stream); + unsigned int getOutput(half** d_voxel_features, unsigned int** d_voxel_indices, std::vector& sparse_shape); +}; \ No newline at end of file diff --git a/trlo/include/center_pointpillars/tensorrt.hpp b/trlo/include/center_pointpillars/tensorrt.hpp new file mode 100644 index 0000000..2c612ce --- /dev/null +++ b/trlo/include/center_pointpillars/tensorrt.hpp @@ -0,0 +1,52 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef TENSORRT_HPP +#define TENSORRT_HPP + +#include +#include +#include + +namespace TensorRT{ + + class Engine{ + public: + virtual int64_t getBindingNumel(const std::string& name) = 0; + virtual std::vector getBindingDims(const std::string& name) = 0; + virtual bool forward(const std::initializer_list& buffers, void* stream = nullptr) = 0; + virtual void print() = 0; + }; + + std::shared_ptr load(const std::string& file); +}; + +#endif // TENSORRT_HPP \ No newline at end of file diff --git a/trlo/include/center_pointpillars/timer.hpp b/trlo/include/center_pointpillars/timer.hpp new file mode 100644 index 0000000..0955d8e --- /dev/null +++ b/trlo/include/center_pointpillars/timer.hpp @@ -0,0 +1,70 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#ifndef TIMER_HPP +#define TIMER_HPP + +#include "common.h" + +class EventTimer{ +public: + EventTimer(){ + checkCudaErrors(cudaEventCreate(&begin_)); + checkCudaErrors(cudaEventCreate(&end_)); + } + + virtual ~EventTimer(){ + checkCudaErrors(cudaEventDestroy(begin_)); + checkCudaErrors(cudaEventDestroy(end_)); + } + + void start(cudaStream_t stream){ + checkCudaErrors(cudaEventRecord(begin_, stream)); + } + + float stop(const char* prefix = "timer", bool print = true){ + float times = 0; + checkCudaErrors(cudaEventRecord(end_, stream_)); + checkCudaErrors(cudaEventSynchronize(end_)); + checkCudaErrors(cudaEventElapsedTime(×, begin_, end_)); + if(print) printf("[TIME] %s:\t\t%.5f ms\n", prefix, times); + return times; + } + +private: + cudaStream_t stream_ = nullptr; + cudaEvent_t begin_ = nullptr, end_ = nullptr; +}; + + + + +#endif // TIMER_HPP \ No newline at end of file diff --git a/trlo/include/nano_gicp/gicp/gicp_settings.hpp b/trlo/include/nano_gicp/gicp/gicp_settings.hpp new file mode 100644 index 0000000..160c0e4 --- /dev/null +++ b/trlo/include/nano_gicp/gicp/gicp_settings.hpp @@ -0,0 +1,51 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * BSD 3-Clause License + * + * Copyright (c) 2020, SMRT-AIST + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +#ifndef NANO_GICP_NANO_SETTINGS_HPP +#define NANO_GICP_NANO_SETTINGS_HPP + +namespace nano_gicp { + + enum class RegularizationMethod { NONE, MIN_EIG, NORMALIZED_MIN_EIG, PLANE, FROBENIUS }; + +} + +#endif \ No newline at end of file diff --git a/trlo/include/nano_gicp/gicp/so3.hpp b/trlo/include/nano_gicp/gicp/so3.hpp new file mode 100644 index 0000000..4f58538 --- /dev/null +++ b/trlo/include/nano_gicp/gicp/so3.hpp @@ -0,0 +1,122 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * BSD 3-Clause License + * + * Copyright (c) 2020, SMRT-AIST + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +#ifndef NANO_GICP_SO3_HPP +#define NANO_GICP_SO3_HPP + +#include +#include + +namespace nano_gicp { + +inline Eigen::Matrix3f skew(const Eigen::Vector3f& x) { + Eigen::Matrix3f skew = Eigen::Matrix3f::Zero(); + skew(0, 1) = -x[2]; + skew(0, 2) = x[1]; + skew(1, 0) = x[2]; + skew(1, 2) = -x[0]; + skew(2, 0) = -x[1]; + skew(2, 1) = x[0]; + + return skew; +} + +inline Eigen::Matrix3d skewd(const Eigen::Vector3d& x) { + Eigen::Matrix3d skew = Eigen::Matrix3d::Zero(); + skew(0, 1) = -x[2]; + skew(0, 2) = x[1]; + skew(1, 0) = x[2]; + skew(1, 2) = -x[0]; + skew(2, 0) = -x[1]; + skew(2, 1) = x[0]; + + return skew; +} + +/* + * SO3 expmap code taken from Sophus + * https://github.com/strasdat/Sophus/blob/593db47500ea1a2de5f0e6579c86147991509c59/sophus/so3.hpp#L585 + * + * Copyright 2011-2017 Hauke Strasdat + * 2012-2017 Steven Lovegrove + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to + * deal in the Software without restriction, including without limitation the + * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or + * sell copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS + * IN THE SOFTWARE. + */ +inline Eigen::Quaterniond so3_exp(const Eigen::Vector3d& omega) { + double theta_sq = omega.dot(omega); + + double theta; + double imag_factor; + double real_factor; + if(theta_sq < 1e-10) { + theta = 0; + double theta_quad = theta_sq * theta_sq; + imag_factor = 0.5 - 1.0 / 48.0 * theta_sq + 1.0 / 3840.0 * theta_quad; + real_factor = 1.0 - 1.0 / 8.0 * theta_sq + 1.0 / 384.0 * theta_quad; + } else { + theta = std::sqrt(theta_sq); + double half_theta = 0.5 * theta; + imag_factor = std::sin(half_theta) / theta; + real_factor = std::cos(half_theta); + } + + return Eigen::Quaterniond(real_factor, imag_factor * omega.x(), imag_factor * omega.y(), imag_factor * omega.z()); +} + +} // namespace nano_gicp + +#endif \ No newline at end of file diff --git a/trlo/include/nano_gicp/impl/lsq_registration_impl.hpp b/trlo/include/nano_gicp/impl/lsq_registration_impl.hpp new file mode 100644 index 0000000..95787ae --- /dev/null +++ b/trlo/include/nano_gicp/impl/lsq_registration_impl.hpp @@ -0,0 +1,210 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * BSD 3-Clause License + * + * Copyright (c) 2020, SMRT-AIST + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +#include + +#include +#include + +namespace nano_gicp { + +template +LsqRegistration::LsqRegistration() { + this->reg_name_ = "LsqRegistration"; + max_iterations_ = 64; + rotation_epsilon_ = 2e-3; + transformation_epsilon_ = 5e-4; + + lsq_optimizer_type_ = LSQ_OPTIMIZER_TYPE::LevenbergMarquardt; + lm_debug_print_ = false; + lm_max_iterations_ = 10; + lm_init_lambda_factor_ = 1e-9; + lm_lambda_ = -1.0; + + final_hessian_.setIdentity(); +} + +template +LsqRegistration::~LsqRegistration() {} + +template +void LsqRegistration::setRotationEpsilon(double eps) { + rotation_epsilon_ = eps; +} + +template +void LsqRegistration::setInitialLambdaFactor(double init_lambda_factor) { + lm_init_lambda_factor_ = init_lambda_factor; +} + +template +void LsqRegistration::setDebugPrint(bool lm_debug_print) { + lm_debug_print_ = lm_debug_print; +} + +template +const Eigen::Matrix& LsqRegistration::getFinalHessian() const { + return final_hessian_; +} + +template +void LsqRegistration::computeTransformation(PointCloudSource& output, const Matrix4& guess) { + Eigen::Isometry3d x0 = Eigen::Isometry3d(guess.template cast()); + + lm_lambda_ = -1.0; + converged_ = false; + + if (lm_debug_print_) { + std::cout << "********************************************" << std::endl; + std::cout << "***************** optimize *****************" << std::endl; + std::cout << "********************************************" << std::endl; + } + + for (int i = 0; i < max_iterations_ && !converged_; i++) { + nr_iterations_ = i; + + Eigen::Isometry3d delta; + if (!step_optimize(x0, delta)) { + std::cerr << "lm not converged!!" << std::endl; + break; + } + + converged_ = is_converged(delta); + } + + final_transformation_ = x0.cast().matrix(); + pcl::transformPointCloud(*input_, output, final_transformation_); +} + +template +bool LsqRegistration::is_converged(const Eigen::Isometry3d& delta) const { + double accum = 0.0; + Eigen::Matrix3d R = delta.linear() - Eigen::Matrix3d::Identity(); + Eigen::Vector3d t = delta.translation(); + + Eigen::Matrix3d r_delta = 1.0 / rotation_epsilon_ * R.array().abs(); + Eigen::Vector3d t_delta = 1.0 / transformation_epsilon_ * t.array().abs(); + + return std::max(r_delta.maxCoeff(), t_delta.maxCoeff()) < 1; +} + +template +bool LsqRegistration::step_optimize(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta) { + switch (lsq_optimizer_type_) { + case LSQ_OPTIMIZER_TYPE::LevenbergMarquardt: + return step_lm(x0, delta); + case LSQ_OPTIMIZER_TYPE::GaussNewton: + return step_gn(x0, delta); + } + + return step_lm(x0, delta); +} + +template +bool LsqRegistration::step_gn(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta) { + Eigen::Matrix H; + Eigen::Matrix b; + double y0 = linearize(x0, &H, &b); + + Eigen::LDLT> solver(H); + Eigen::Matrix d = solver.solve(-b); + + delta.setIdentity(); + delta.linear() = so3_exp(d.head<3>()).toRotationMatrix(); + delta.translation() = d.tail<3>(); + + x0 = delta * x0; + final_hessian_ = H; + + return true; +} + +template +bool LsqRegistration::step_lm(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta) { + Eigen::Matrix H; + Eigen::Matrix b; + double y0 = linearize(x0, &H, &b); + + if (lm_lambda_ < 0.0) { + lm_lambda_ = lm_init_lambda_factor_ * H.diagonal().array().abs().maxCoeff(); + } + + double nu = 2.0; + for (int i = 0; i < lm_max_iterations_; i++) { + Eigen::LDLT> solver(H + lm_lambda_ * Eigen::Matrix::Identity()); + Eigen::Matrix d = solver.solve(-b); + + delta.setIdentity(); + delta.linear() = so3_exp(d.head<3>()).toRotationMatrix(); + delta.translation() = d.tail<3>(); + + Eigen::Isometry3d xi = delta * x0; + double yi = compute_error(xi); + double rho = (y0 - yi) / (d.dot(lm_lambda_ * d - b)); + + if (lm_debug_print_) { + if (i == 0) { + std::cout << boost::format("--- LM optimization ---\n%5s %15s %15s %15s %15s %15s %5s\n") % "i" % "y0" % "yi" % "rho" % "lambda" % "|delta|" % "dec"; + } + char dec = rho > 0.0 ? 'x' : ' '; + std::cout << boost::format("%5d %15g %15g %15g %15g %15g %5c") % i % y0 % yi % rho % lm_lambda_ % d.norm() % dec << std::endl; + } + + if (rho < 0) { + if (is_converged(delta)) { + return true; + } + + lm_lambda_ = nu * lm_lambda_; + nu = 2 * nu; + continue; + } + + x0 = xi; + lm_lambda_ = lm_lambda_ * std::max(1.0 / 3.0, 1 - std::pow(2 * rho - 1, 3)); + final_hessian_ = H; + return true; + } + + return false; +} + +} // namespace nano_gicp \ No newline at end of file diff --git a/trlo/include/nano_gicp/impl/nano_gicp_impl.hpp b/trlo/include/nano_gicp/impl/nano_gicp_impl.hpp new file mode 100644 index 0000000..8663846 --- /dev/null +++ b/trlo/include/nano_gicp/impl/nano_gicp_impl.hpp @@ -0,0 +1,361 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * BSD 3-Clause License + * + * Copyright (c) 2020, SMRT-AIST + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +#ifndef NANO_GICP_NANO_GICP_IMPL_HPP +#define NANO_GICP_NANO_GICP_IMPL_HPP + +#include + +namespace nano_gicp { + +template +NanoGICP::NanoGICP() { +#ifdef _OPENMP + num_threads_ = omp_get_max_threads(); +#else + num_threads_ = 1; +#endif + + k_correspondences_ = 20; + reg_name_ = "NanoGICP"; + corr_dist_threshold_ = std::numeric_limits::max(); + + regularization_method_ = RegularizationMethod::PLANE; + source_kdtree_.reset(new nanoflann::KdTreeFLANN); + target_kdtree_.reset(new nanoflann::KdTreeFLANN); +} + +template +NanoGICP::~NanoGICP() {} + +template +void NanoGICP::setNumThreads(int n) { + num_threads_ = n; + +#ifdef _OPENMP + if (n == 0) { + num_threads_ = omp_get_max_threads(); + } +#endif +} + +template +void NanoGICP::setCorrespondenceRandomness(int k) { + k_correspondences_ = k; +} + +template +void NanoGICP::setRegularizationMethod(RegularizationMethod method) { + regularization_method_ = method; +} + +template +void NanoGICP::swapSourceAndTarget() { + input_.swap(target_); + source_kdtree_.swap(target_kdtree_); + source_covs_.swap(target_covs_); + + correspondences_.clear(); + sq_distances_.clear(); +} + +template +void NanoGICP::clearSource() { + input_.reset(); + source_covs_.clear(); +} + +template +void NanoGICP::clearTarget() { + target_.reset(); + target_covs_.clear(); +} + +template +void NanoGICP::registerInputSource(const PointCloudSourceConstPtr& cloud) { + if (input_ == cloud) { + return; + } + pcl::Registration::setInputSource(cloud); +} + +template +void NanoGICP::setInputSource(const PointCloudSourceConstPtr& cloud) { + if (input_ == cloud) { + return; + } + + pcl::Registration::setInputSource(cloud); + source_kdtree_->setInputCloud(cloud); + source_covs_.clear(); +} + +template +void NanoGICP::setInputTarget(const PointCloudTargetConstPtr& cloud) { + if (target_ == cloud) { + return; + } + pcl::Registration::setInputTarget(cloud); + target_kdtree_->setInputCloud(cloud); + target_covs_.clear(); +} + +template +void NanoGICP::setSourceCovariances(const std::vector>& covs) { + source_covs_ = covs; +} + +template +void NanoGICP::setTargetCovariances(const std::vector>& covs) { + target_covs_ = covs; +} + +template +bool NanoGICP::calculateSourceCovariances() { + return calculate_covariances(input_, *source_kdtree_, source_covs_); +} + +template +bool NanoGICP::calculateTargetCovariances() { + return calculate_covariances(target_, *target_kdtree_, target_covs_); +} + +template +void NanoGICP::computeTransformation(PointCloudSource& output, const Matrix4& guess) { + if (source_covs_.size() != input_->size()) { + calculateSourceCovariances(); + } + if (target_covs_.size() != target_->size()) { + calculateTargetCovariances(); + } + + LsqRegistration::computeTransformation(output, guess); +} + +template +void NanoGICP::update_correspondences(const Eigen::Isometry3d& trans) { + assert(source_covs_.size() == input_->size()); + assert(target_covs_.size() == target_->size()); + + Eigen::Isometry3f trans_f = trans.cast(); + + correspondences_.resize(input_->size()); + sq_distances_.resize(input_->size()); + mahalanobis_.resize(input_->size()); + + std::vector k_indices(1); + std::vector k_sq_dists(1); + +#pragma omp parallel for num_threads(num_threads_) firstprivate(k_indices, k_sq_dists) schedule(guided, 8) + for (int i = 0; i < input_->size(); i++) { + PointTarget pt; + pt.getVector4fMap() = trans_f * input_->at(i).getVector4fMap(); + + target_kdtree_->nearestKSearch(pt, 1, k_indices, k_sq_dists); + + sq_distances_[i] = k_sq_dists[0]; + correspondences_[i] = k_sq_dists[0] < corr_dist_threshold_ * corr_dist_threshold_ ? k_indices[0] : -1; + + if (correspondences_[i] < 0) { + continue; + } + + const int target_index = correspondences_[i]; + const auto& cov_A = source_covs_[i]; + const auto& cov_B = target_covs_[target_index]; + + Eigen::Matrix4d RCR = cov_B + trans.matrix() * cov_A * trans.matrix().transpose(); + RCR(3, 3) = 1.0; + + mahalanobis_[i] = RCR.inverse(); + mahalanobis_[i](3, 3) = 0.0f; + } +} + +template +double NanoGICP::linearize(const Eigen::Isometry3d& trans, Eigen::Matrix* H, Eigen::Matrix* b) { + update_correspondences(trans); + + double sum_errors = 0.0; + std::vector, Eigen::aligned_allocator>> Hs(num_threads_); + std::vector, Eigen::aligned_allocator>> bs(num_threads_); + for (int i = 0; i < num_threads_; i++) { + Hs[i].setZero(); + bs[i].setZero(); + } + +#pragma omp parallel for num_threads(num_threads_) reduction(+ : sum_errors) schedule(guided, 8) + for (int i = 0; i < input_->size(); i++) { + int target_index = correspondences_[i]; + if (target_index < 0) { + continue; + } + + const Eigen::Vector4d mean_A = input_->at(i).getVector4fMap().template cast(); + const auto& cov_A = source_covs_[i]; + + const Eigen::Vector4d mean_B = target_->at(target_index).getVector4fMap().template cast(); + const auto& cov_B = target_covs_[target_index]; + + const Eigen::Vector4d transed_mean_A = trans * mean_A; + const Eigen::Vector4d error = mean_B - transed_mean_A; + + sum_errors += error.transpose() * mahalanobis_[i] * error; + + if (H == nullptr || b == nullptr) { + continue; + } + + Eigen::Matrix dtdx0 = Eigen::Matrix::Zero(); + dtdx0.block<3, 3>(0, 0) = skewd(transed_mean_A.head<3>()); + dtdx0.block<3, 3>(0, 3) = -Eigen::Matrix3d::Identity(); + + Eigen::Matrix jlossexp = dtdx0; + + Eigen::Matrix Hi = jlossexp.transpose() * mahalanobis_[i] * jlossexp; + Eigen::Matrix bi = jlossexp.transpose() * mahalanobis_[i] * error; + + Hs[omp_get_thread_num()] += Hi; + bs[omp_get_thread_num()] += bi; + } + + if (H && b) { + H->setZero(); + b->setZero(); + for (int i = 0; i < num_threads_; i++) { + (*H) += Hs[i]; + (*b) += bs[i]; + } + } + + return sum_errors; +} + +template +double NanoGICP::compute_error(const Eigen::Isometry3d& trans) { + double sum_errors = 0.0; + +#pragma omp parallel for num_threads(num_threads_) reduction(+ : sum_errors) schedule(guided, 8) + for (int i = 0; i < input_->size(); i++) { + int target_index = correspondences_[i]; + if (target_index < 0) { + continue; + } + + const Eigen::Vector4d mean_A = input_->at(i).getVector4fMap().template cast(); + const auto& cov_A = source_covs_[i]; + + const Eigen::Vector4d mean_B = target_->at(target_index).getVector4fMap().template cast(); + const auto& cov_B = target_covs_[target_index]; + + const Eigen::Vector4d transed_mean_A = trans * mean_A; + const Eigen::Vector4d error = mean_B - transed_mean_A; + + sum_errors += error.transpose() * mahalanobis_[i] * error; + } + + return sum_errors; +} + +template +template +bool NanoGICP::calculate_covariances( + const typename pcl::PointCloud::ConstPtr& cloud, + nanoflann::KdTreeFLANN& kdtree, + std::vector>& covariances) { + if (kdtree.getInputCloud() != cloud) { + kdtree.setInputCloud(cloud); + } + covariances.resize(cloud->size()); + +#pragma omp parallel for num_threads(num_threads_) schedule(guided, 8) + for (int i = 0; i < cloud->size(); i++) { + std::vector k_indices; + std::vector k_sq_distances; + kdtree.nearestKSearch(cloud->at(i), k_correspondences_, k_indices, k_sq_distances); + + Eigen::Matrix neighbors(4, k_correspondences_); + for (int j = 0; j < k_indices.size(); j++) { + neighbors.col(j) = cloud->at(k_indices[j]).getVector4fMap().template cast(); + } + + neighbors.colwise() -= neighbors.rowwise().mean().eval(); + Eigen::Matrix4d cov = neighbors * neighbors.transpose() / k_correspondences_; + + if (regularization_method_ == RegularizationMethod::NONE) { + covariances[i] = cov; + } else if (regularization_method_ == RegularizationMethod::FROBENIUS) { + double lambda = 1e-3; + Eigen::Matrix3d C = cov.block<3, 3>(0, 0).cast() + lambda * Eigen::Matrix3d::Identity(); + Eigen::Matrix3d C_inv = C.inverse(); + covariances[i].setZero(); + covariances[i].template block<3, 3>(0, 0) = (C_inv / C_inv.norm()).inverse(); + } else { + Eigen::JacobiSVD svd(cov.block<3, 3>(0, 0), Eigen::ComputeFullU | Eigen::ComputeFullV); + Eigen::Vector3d values; + + switch (regularization_method_) { + default: + std::cerr << "here must not be reached" << std::endl; + abort(); + case RegularizationMethod::PLANE: + values = Eigen::Vector3d(1, 1, 1e-3); + break; + case RegularizationMethod::MIN_EIG: + values = svd.singularValues().array().max(1e-3); + break; + case RegularizationMethod::NORMALIZED_MIN_EIG: + values = svd.singularValues() / svd.singularValues().maxCoeff(); + values = values.array().max(1e-3); + break; + } + + covariances[i].setZero(); + covariances[i].template block<3, 3>(0, 0) = svd.matrixU() * values.asDiagonal() * svd.matrixV().transpose(); + } + } + + return true; +} + +} // namespace nano_gicp + +#endif diff --git a/trlo/include/nano_gicp/impl/nanoflann_impl.hpp b/trlo/include/nano_gicp/impl/nanoflann_impl.hpp new file mode 100644 index 0000000..f86064d --- /dev/null +++ b/trlo/include/nano_gicp/impl/nanoflann_impl.hpp @@ -0,0 +1,2057 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * Software License Agreement (BSD License) + * + * Copyright 2008-2009 Marius Muja (mariusm@cs.ubc.ca). All rights reserved. + * Copyright 2008-2009 David G. Lowe (lowe@cs.ubc.ca). All rights reserved. + * Copyright 2011-2021 Jose Luis Blanco (joseluisblancoc@gmail.com). + * All rights reserved. + * + * THE BSD LICENSE + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES + * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. + * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, + * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY + * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF + * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +/** \mainpage nanoflann C++ API documentation + * nanoflann is a C++ header-only library for building KD-Trees, mostly + * optimized for 2D or 3D point clouds. + * + * nanoflann does not require compiling or installing, just an + * #include in your code. + * + * See: + * - C++ API organized by modules + * - Online README + * - Doxygen + * documentation + */ + +#ifndef NANOFLANN_HPP_ +#define NANOFLANN_HPP_ + +#include +#include +#include +#include // for abs() +#include // for fwrite() +#include // for abs() +#include +#include // std::reference_wrapper +#include +#include + +/** Library version: 0xMmP (M=Major,m=minor,P=patch) */ +#define NANOFLANN_VERSION 0x132 + +// Avoid conflicting declaration of min/max macros in windows headers +#if !defined(NOMINMAX) && \ + (defined(_WIN32) || defined(_WIN32_) || defined(WIN32) || defined(_WIN64)) +#define NOMINMAX +#ifdef max +#undef max +#undef min +#endif +#endif + +namespace nanoflann { +/** @addtogroup nanoflann_grp nanoflann C++ library for ANN + * @{ */ + +/** the PI constant (required to avoid MSVC missing symbols) */ +template T pi_const() { + return static_cast(3.14159265358979323846); +} + +/** + * Traits if object is resizable and assignable (typically has a resize | assign + * method) + */ +template struct has_resize : std::false_type {}; + +template +struct has_resize().resize(1), 0)> + : std::true_type {}; + +template struct has_assign : std::false_type {}; + +template +struct has_assign().assign(1, 0), 0)> + : std::true_type {}; + +/** + * Free function to resize a resizable object + */ +template +inline typename std::enable_if::value, void>::type +resize(Container &c, const size_t nElements) { + c.resize(nElements); +} + +/** + * Free function that has no effects on non resizable containers (e.g. + * std::array) It raises an exception if the expected size does not match + */ +template +inline typename std::enable_if::value, void>::type +resize(Container &c, const size_t nElements) { + if (nElements != c.size()) + throw std::logic_error("Try to change the size of a std::array."); +} + +/** + * Free function to assign to a container + */ +template +inline typename std::enable_if::value, void>::type +assign(Container &c, const size_t nElements, const T &value) { + c.assign(nElements, value); +} + +/** + * Free function to assign to a std::array + */ +template +inline typename std::enable_if::value, void>::type +assign(Container &c, const size_t nElements, const T &value) { + for (size_t i = 0; i < nElements; i++) + c[i] = value; +} + +/** @addtogroup result_sets_grp Result set classes + * @{ */ +template +class KNNResultSet { +public: + typedef _DistanceType DistanceType; + typedef _IndexType IndexType; + typedef _CountType CountType; + +private: + IndexType *indices; + DistanceType *dists; + CountType capacity; + CountType count; + +public: + inline KNNResultSet(CountType capacity_) + : indices(0), dists(0), capacity(capacity_), count(0) {} + + inline void init(IndexType *indices_, DistanceType *dists_) { + indices = indices_; + dists = dists_; + count = 0; + if (capacity) + dists[capacity - 1] = (std::numeric_limits::max)(); + } + + inline CountType size() const { return count; } + + inline bool full() const { return count == capacity; } + + /** + * Called during search to add an element matching the criteria. + * @return true if the search should be continued, false if the results are + * sufficient + */ + inline bool addPoint(DistanceType dist, IndexType index) { + CountType i; + for (i = count; i > 0; --i) { +#ifdef NANOFLANN_FIRST_MATCH // If defined and two points have the same + // distance, the one with the lowest-index will be + // returned first. + if ((dists[i - 1] > dist) || + ((dist == dists[i - 1]) && (indices[i - 1] > index))) { +#else + if (dists[i - 1] > dist) { +#endif + if (i < capacity) { + dists[i] = dists[i - 1]; + indices[i] = indices[i - 1]; + } + } else + break; + } + if (i < capacity) { + dists[i] = dist; + indices[i] = index; + } + if (count < capacity) + count++; + + // tell caller that the search shall continue + return true; + } + + inline DistanceType worstDist() const { return dists[capacity - 1]; } +}; + +/** operator "<" for std::sort() */ +struct IndexDist_Sorter { + /** PairType will be typically: std::pair */ + template + inline bool operator()(const PairType &p1, const PairType &p2) const { + return p1.second < p2.second; + } +}; + +/** + * A result-set class used when performing a radius based search. + */ +template +class RadiusResultSet { +public: + typedef _DistanceType DistanceType; + typedef _IndexType IndexType; + +public: + const DistanceType radius; + + std::vector> &m_indices_dists; + + inline RadiusResultSet( + DistanceType radius_, + std::vector> &indices_dists) + : radius(radius_), m_indices_dists(indices_dists) { + init(); + } + + inline void init() { clear(); } + inline void clear() { m_indices_dists.clear(); } + + inline size_t size() const { return m_indices_dists.size(); } + + inline bool full() const { return true; } + + /** + * Called during search to add an element matching the criteria. + * @return true if the search should be continued, false if the results are + * sufficient + */ + inline bool addPoint(DistanceType dist, IndexType index) { + if (dist < radius) + m_indices_dists.push_back(std::make_pair(index, dist)); + return true; + } + + inline DistanceType worstDist() const { return radius; } + + /** + * Find the worst result (furtherest neighbor) without copying or sorting + * Pre-conditions: size() > 0 + */ + std::pair worst_item() const { + if (m_indices_dists.empty()) + throw std::runtime_error("Cannot invoke RadiusResultSet::worst_item() on " + "an empty list of results."); + typedef + typename std::vector>::const_iterator + DistIt; + DistIt it = std::max_element(m_indices_dists.begin(), m_indices_dists.end(), + IndexDist_Sorter()); + return *it; + } +}; + +/** @} */ + +/** @addtogroup loadsave_grp Load/save auxiliary functions + * @{ */ +template +void save_value(FILE *stream, const T &value, size_t count = 1) { + fwrite(&value, sizeof(value), count, stream); +} + +template +void save_value(FILE *stream, const std::vector &value) { + size_t size = value.size(); + fwrite(&size, sizeof(size_t), 1, stream); + fwrite(&value[0], sizeof(T), size, stream); +} + +template +void load_value(FILE *stream, T &value, size_t count = 1) { + size_t read_cnt = fread(&value, sizeof(value), count, stream); + if (read_cnt != count) { + throw std::runtime_error("Cannot read from file"); + } +} + +template void load_value(FILE *stream, std::vector &value) { + size_t size; + size_t read_cnt = fread(&size, sizeof(size_t), 1, stream); + if (read_cnt != 1) { + throw std::runtime_error("Cannot read from file"); + } + value.resize(size); + read_cnt = fread(&value[0], sizeof(T), size, stream); + if (read_cnt != size) { + throw std::runtime_error("Cannot read from file"); + } +} +/** @} */ + +/** @addtogroup metric_grp Metric (distance) classes + * @{ */ + +struct Metric {}; + +/** Manhattan distance functor (generic version, optimized for + * high-dimensionality data sets). Corresponding distance traits: + * nanoflann::metric_L1 \tparam T Type of the elements (e.g. double, float, + * uint8_t) \tparam _DistanceType Type of distance variables (must be signed) + * (e.g. float, double, int64_t) + */ +template +struct L1_Adaptor { + typedef T ElementType; + typedef _DistanceType DistanceType; + + const DataSource &data_source; + + L1_Adaptor(const DataSource &_data_source) : data_source(_data_source) {} + + inline DistanceType evalMetric(const T *a, const size_t b_idx, size_t size, + DistanceType worst_dist = -1) const { + DistanceType result = DistanceType(); + const T *last = a + size; + const T *lastgroup = last - 3; + size_t d = 0; + + /* Process 4 items with each loop for efficiency. */ + while (a < lastgroup) { + const DistanceType diff0 = + std::abs(a[0] - data_source.kdtree_get_pt(b_idx, d++)); + const DistanceType diff1 = + std::abs(a[1] - data_source.kdtree_get_pt(b_idx, d++)); + const DistanceType diff2 = + std::abs(a[2] - data_source.kdtree_get_pt(b_idx, d++)); + const DistanceType diff3 = + std::abs(a[3] - data_source.kdtree_get_pt(b_idx, d++)); + result += diff0 + diff1 + diff2 + diff3; + a += 4; + if ((worst_dist > 0) && (result > worst_dist)) { + return result; + } + } + /* Process last 0-3 components. Not needed for standard vector lengths. */ + while (a < last) { + result += std::abs(*a++ - data_source.kdtree_get_pt(b_idx, d++)); + } + return result; + } + + template + inline DistanceType accum_dist(const U a, const V b, const size_t) const { + return std::abs(a - b); + } +}; + +/** Squared Euclidean distance functor (generic version, optimized for + * high-dimensionality data sets). Corresponding distance traits: + * nanoflann::metric_L2 \tparam T Type of the elements (e.g. double, float, + * uint8_t) \tparam _DistanceType Type of distance variables (must be signed) + * (e.g. float, double, int64_t) + */ +template +struct L2_Adaptor { + typedef T ElementType; + typedef _DistanceType DistanceType; + + const DataSource &data_source; + + L2_Adaptor(const DataSource &_data_source) : data_source(_data_source) {} + + inline DistanceType evalMetric(const T *a, const size_t b_idx, size_t size, + DistanceType worst_dist = -1) const { + DistanceType result = DistanceType(); + const T *last = a + size; + const T *lastgroup = last - 3; + size_t d = 0; + + /* Process 4 items with each loop for efficiency. */ + while (a < lastgroup) { + const DistanceType diff0 = a[0] - data_source.kdtree_get_pt(b_idx, d++); + const DistanceType diff1 = a[1] - data_source.kdtree_get_pt(b_idx, d++); + const DistanceType diff2 = a[2] - data_source.kdtree_get_pt(b_idx, d++); + const DistanceType diff3 = a[3] - data_source.kdtree_get_pt(b_idx, d++); + result += diff0 * diff0 + diff1 * diff1 + diff2 * diff2 + diff3 * diff3; + a += 4; + if ((worst_dist > 0) && (result > worst_dist)) { + return result; + } + } + /* Process last 0-3 components. Not needed for standard vector lengths. */ + while (a < last) { + const DistanceType diff0 = *a++ - data_source.kdtree_get_pt(b_idx, d++); + result += diff0 * diff0; + } + return result; + } + + template + inline DistanceType accum_dist(const U a, const V b, const size_t) const { + return (a - b) * (a - b); + } +}; + +/** Squared Euclidean (L2) distance functor (suitable for low-dimensionality + * datasets, like 2D or 3D point clouds) Corresponding distance traits: + * nanoflann::metric_L2_Simple \tparam T Type of the elements (e.g. double, + * float, uint8_t) \tparam _DistanceType Type of distance variables (must be + * signed) (e.g. float, double, int64_t) + */ +template +struct L2_Simple_Adaptor { + typedef T ElementType; + typedef _DistanceType DistanceType; + + const DataSource &data_source; + + L2_Simple_Adaptor(const DataSource &_data_source) + : data_source(_data_source) {} + + inline DistanceType evalMetric(const T *a, const size_t b_idx, + size_t size) const { + DistanceType result = DistanceType(); + for (size_t i = 0; i < size; ++i) { + const DistanceType diff = a[i] - data_source.kdtree_get_pt(b_idx, i); + result += diff * diff; + } + return result; + } + + template + inline DistanceType accum_dist(const U a, const V b, const size_t) const { + return (a - b) * (a - b); + } +}; + +/** SO2 distance functor + * Corresponding distance traits: nanoflann::metric_SO2 + * \tparam T Type of the elements (e.g. double, float) + * \tparam _DistanceType Type of distance variables (must be signed) (e.g. + * float, double) orientation is constrained to be in [-pi, pi] + */ +template +struct SO2_Adaptor { + typedef T ElementType; + typedef _DistanceType DistanceType; + + const DataSource &data_source; + + SO2_Adaptor(const DataSource &_data_source) : data_source(_data_source) {} + + inline DistanceType evalMetric(const T *a, const size_t b_idx, + size_t size) const { + return accum_dist(a[size - 1], data_source.kdtree_get_pt(b_idx, size - 1), + size - 1); + } + + /** Note: this assumes that input angles are already in the range [-pi,pi] */ + template + inline DistanceType accum_dist(const U a, const V b, const size_t) const { + DistanceType result = DistanceType(); + DistanceType PI = pi_const(); + result = b - a; + if (result > PI) + result -= 2 * PI; + else if (result < -PI) + result += 2 * PI; + return result; + } +}; + +/** SO3 distance functor (Uses L2_Simple) + * Corresponding distance traits: nanoflann::metric_SO3 + * \tparam T Type of the elements (e.g. double, float) + * \tparam _DistanceType Type of distance variables (must be signed) (e.g. + * float, double) + */ +template +struct SO3_Adaptor { + typedef T ElementType; + typedef _DistanceType DistanceType; + + L2_Simple_Adaptor distance_L2_Simple; + + SO3_Adaptor(const DataSource &_data_source) + : distance_L2_Simple(_data_source) {} + + inline DistanceType evalMetric(const T *a, const size_t b_idx, + size_t size) const { + return distance_L2_Simple.evalMetric(a, b_idx, size); + } + + template + inline DistanceType accum_dist(const U a, const V b, const size_t idx) const { + return distance_L2_Simple.accum_dist(a, b, idx); + } +}; + +/** Metaprogramming helper traits class for the L1 (Manhattan) metric */ +struct metric_L1 : public Metric { + template struct traits { + typedef L1_Adaptor distance_t; + }; +}; +/** Metaprogramming helper traits class for the L2 (Euclidean) metric */ +struct metric_L2 : public Metric { + template struct traits { + typedef L2_Adaptor distance_t; + }; +}; +/** Metaprogramming helper traits class for the L2_simple (Euclidean) metric */ +struct metric_L2_Simple : public Metric { + template struct traits { + typedef L2_Simple_Adaptor distance_t; + }; +}; +/** Metaprogramming helper traits class for the SO3_InnerProdQuat metric */ +struct metric_SO2 : public Metric { + template struct traits { + typedef SO2_Adaptor distance_t; + }; +}; +/** Metaprogramming helper traits class for the SO3_InnerProdQuat metric */ +struct metric_SO3 : public Metric { + template struct traits { + typedef SO3_Adaptor distance_t; + }; +}; + +/** @} */ + +/** @addtogroup param_grp Parameter structs + * @{ */ + +/** Parameters (see README.md) */ +struct KDTreeSingleIndexAdaptorParams { + KDTreeSingleIndexAdaptorParams(size_t _leaf_max_size = 10) + : leaf_max_size(_leaf_max_size) {} + + size_t leaf_max_size; +}; + +/** Search options for KDTreeSingleIndexAdaptor::findNeighbors() */ +struct SearchParams { + /** Note: The first argument (checks_IGNORED_) is ignored, but kept for + * compatibility with the FLANN interface */ + SearchParams(int checks_IGNORED_ = 32, float eps_ = 0, bool sorted_ = true) + : checks(checks_IGNORED_), eps(eps_), sorted(sorted_) {} + + int checks; //!< Ignored parameter (Kept for compatibility with the FLANN + //!< interface). + float eps; //!< search for eps-approximate neighbours (default: 0) + bool sorted; //!< only for radius search, require neighbours sorted by + //!< distance (default: true) +}; +/** @} */ + +/** @addtogroup memalloc_grp Memory allocation + * @{ */ + +/** + * Allocates (using C's malloc) a generic type T. + * + * Params: + * count = number of instances to allocate. + * Returns: pointer (of type T*) to memory buffer + */ +template inline T *allocate(size_t count = 1) { + T *mem = static_cast(::malloc(sizeof(T) * count)); + return mem; +} + +/** + * Pooled storage allocator + * + * The following routines allow for the efficient allocation of storage in + * small chunks from a specified pool. Rather than allowing each structure + * to be freed individually, an entire pool of storage is freed at once. + * This method has two advantages over just using malloc() and free(). First, + * it is far more efficient for allocating small objects, as there is + * no overhead for remembering all the information needed to free each + * object or consolidating fragmented memory. Second, the decision about + * how long to keep an object is made at the time of allocation, and there + * is no need to track down all the objects to free them. + * + */ + +const size_t WORDSIZE = 16; +const size_t BLOCKSIZE = 8192; + +class PooledAllocator { + /* We maintain memory alignment to word boundaries by requiring that all + allocations be in multiples of the machine wordsize. */ + /* Size of machine word in bytes. Must be power of 2. */ + /* Minimum number of bytes requested at a time from the system. Must be + * multiple of WORDSIZE. */ + + size_t remaining; /* Number of bytes left in current block of storage. */ + void *base; /* Pointer to base of current block of storage. */ + void *loc; /* Current location in block to next allocate memory. */ + + void internal_init() { + remaining = 0; + base = NULL; + usedMemory = 0; + wastedMemory = 0; + } + +public: + size_t usedMemory; + size_t wastedMemory; + + /** + Default constructor. Initializes a new pool. + */ + PooledAllocator() { internal_init(); } + + /** + * Destructor. Frees all the memory allocated in this pool. + */ + ~PooledAllocator() { free_all(); } + + /** Frees all allocated memory chunks */ + void free_all() { + while (base != NULL) { + void *prev = + *(static_cast(base)); /* Get pointer to prev block. */ + ::free(base); + base = prev; + } + internal_init(); + } + + /** + * Returns a pointer to a piece of new memory of the given size in bytes + * allocated from the pool. + */ + void *malloc(const size_t req_size) { + /* Round size up to a multiple of wordsize. The following expression + only works for WORDSIZE that is a power of 2, by masking last bits of + incremented size to zero. + */ + const size_t size = (req_size + (WORDSIZE - 1)) & ~(WORDSIZE - 1); + + /* Check whether a new block must be allocated. Note that the first word + of a block is reserved for a pointer to the previous block. + */ + if (size > remaining) { + + wastedMemory += remaining; + + /* Allocate new storage. */ + const size_t blocksize = + (size + sizeof(void *) + (WORDSIZE - 1) > BLOCKSIZE) + ? size + sizeof(void *) + (WORDSIZE - 1) + : BLOCKSIZE; + + // use the standard C malloc to allocate memory + void *m = ::malloc(blocksize); + if (!m) { + fprintf(stderr, "Failed to allocate memory.\n"); + throw std::bad_alloc(); + } + + /* Fill first word of new block with pointer to previous block. */ + static_cast(m)[0] = base; + base = m; + + size_t shift = 0; + // int size_t = (WORDSIZE - ( (((size_t)m) + sizeof(void*)) & + // (WORDSIZE-1))) & (WORDSIZE-1); + + remaining = blocksize - sizeof(void *) - shift; + loc = (static_cast(m) + sizeof(void *) + shift); + } + void *rloc = loc; + loc = static_cast(loc) + size; + remaining -= size; + + usedMemory += size; + + return rloc; + } + + /** + * Allocates (using this pool) a generic type T. + * + * Params: + * count = number of instances to allocate. + * Returns: pointer (of type T*) to memory buffer + */ + template T *allocate(const size_t count = 1) { + T *mem = static_cast(this->malloc(sizeof(T) * count)); + return mem; + } +}; +/** @} */ + +/** @addtogroup nanoflann_metaprog_grp Auxiliary metaprogramming stuff + * @{ */ + +/** Used to declare fixed-size arrays when DIM>0, dynamically-allocated vectors + * when DIM=-1. Fixed size version for a generic DIM: + */ +template struct array_or_vector_selector { + typedef std::array container_t; +}; +/** Dynamic size version */ +template struct array_or_vector_selector<-1, T> { + typedef std::vector container_t; +}; + +/** @} */ + +/** kd-tree base-class + * + * Contains the member functions common to the classes KDTreeSingleIndexAdaptor + * and KDTreeSingleIndexDynamicAdaptor_. + * + * \tparam Derived The name of the class which inherits this class. + * \tparam DatasetAdaptor The user-provided adaptor (see comments above). + * \tparam Distance The distance metric to use, these are all classes derived + * from nanoflann::Metric \tparam DIM Dimensionality of data points (e.g. 3 for + * 3D points) \tparam IndexType Will be typically size_t or int + */ + +template +class KDTreeBaseClass { + +public: + /** Frees the previously-built index. Automatically called within + * buildIndex(). */ + void freeIndex(Derived &obj) { + obj.pool.free_all(); + obj.root_node = NULL; + obj.m_size_at_index_build = 0; + } + + typedef typename Distance::ElementType ElementType; + typedef typename Distance::DistanceType DistanceType; + + /*--------------------- Internal Data Structures --------------------------*/ + struct Node { + /** Union used because a node can be either a LEAF node or a non-leaf node, + * so both data fields are never used simultaneously */ + union { + struct leaf { + IndexType left, right; //!< Indices of points in leaf node + } lr; + struct nonleaf { + int divfeat; //!< Dimension used for subdivision. + DistanceType divlow, divhigh; //!< The values used for subdivision. + } sub; + } node_type; + Node *child1, *child2; //!< Child nodes (both=NULL mean its a leaf node) + }; + + typedef Node *NodePtr; + + struct Interval { + ElementType low, high; + }; + + /** + * Array of indices to vectors in the dataset. + */ + std::vector vind; + + NodePtr root_node; + + size_t m_leaf_max_size; + + size_t m_size; //!< Number of current points in the dataset + size_t m_size_at_index_build; //!< Number of points in the dataset when the + //!< index was built + int dim; //!< Dimensionality of each data point + + /** Define "BoundingBox" as a fixed-size or variable-size container depending + * on "DIM" */ + typedef + typename array_or_vector_selector::container_t BoundingBox; + + /** Define "distance_vector_t" as a fixed-size or variable-size container + * depending on "DIM" */ + typedef typename array_or_vector_selector::container_t + distance_vector_t; + + /** The KD-tree used to find neighbours */ + + BoundingBox root_bbox; + + /** + * Pooled memory allocator. + * + * Using a pooled memory allocator is more efficient + * than allocating memory directly when there is a large + * number small of memory allocations. + */ + PooledAllocator pool; + + /** Returns number of points in dataset */ + size_t size(const Derived &obj) const { return obj.m_size; } + + /** Returns the length of each point in the dataset */ + size_t veclen(const Derived &obj) { + return static_cast(DIM > 0 ? DIM : obj.dim); + } + + /// Helper accessor to the dataset points: + inline ElementType dataset_get(const Derived &obj, size_t idx, + int component) const { + return obj.dataset.kdtree_get_pt(idx, component); + } + + /** + * Computes the inde memory usage + * Returns: memory used by the index + */ + size_t usedMemory(Derived &obj) { + return obj.pool.usedMemory + obj.pool.wastedMemory + + obj.dataset.kdtree_get_point_count() * + sizeof(IndexType); // pool memory and vind array memory + } + + void computeMinMax(const Derived &obj, IndexType *ind, IndexType count, + int element, ElementType &min_elem, + ElementType &max_elem) { + min_elem = dataset_get(obj, ind[0], element); + max_elem = dataset_get(obj, ind[0], element); + for (IndexType i = 1; i < count; ++i) { + ElementType val = dataset_get(obj, ind[i], element); + if (val < min_elem) + min_elem = val; + if (val > max_elem) + max_elem = val; + } + } + + /** + * Create a tree node that subdivides the list of vecs from vind[first] + * to vind[last]. The routine is called recursively on each sublist. + * + * @param left index of the first vector + * @param right index of the last vector + */ + NodePtr divideTree(Derived &obj, const IndexType left, const IndexType right, + BoundingBox &bbox) { + NodePtr node = obj.pool.template allocate(); // allocate memory + + /* If too few exemplars remain, then make this a leaf node. */ + if ((right - left) <= static_cast(obj.m_leaf_max_size)) { + node->child1 = node->child2 = NULL; /* Mark as leaf node. */ + node->node_type.lr.left = left; + node->node_type.lr.right = right; + + // compute bounding-box of leaf points + for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) { + bbox[i].low = dataset_get(obj, obj.vind[left], i); + bbox[i].high = dataset_get(obj, obj.vind[left], i); + } + for (IndexType k = left + 1; k < right; ++k) { + for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) { + if (bbox[i].low > dataset_get(obj, obj.vind[k], i)) + bbox[i].low = dataset_get(obj, obj.vind[k], i); + if (bbox[i].high < dataset_get(obj, obj.vind[k], i)) + bbox[i].high = dataset_get(obj, obj.vind[k], i); + } + } + } else { + IndexType idx; + int cutfeat; + DistanceType cutval; + middleSplit_(obj, &obj.vind[0] + left, right - left, idx, cutfeat, cutval, + bbox); + + node->node_type.sub.divfeat = cutfeat; + + BoundingBox left_bbox(bbox); + left_bbox[cutfeat].high = cutval; + node->child1 = divideTree(obj, left, left + idx, left_bbox); + + BoundingBox right_bbox(bbox); + right_bbox[cutfeat].low = cutval; + node->child2 = divideTree(obj, left + idx, right, right_bbox); + + node->node_type.sub.divlow = left_bbox[cutfeat].high; + node->node_type.sub.divhigh = right_bbox[cutfeat].low; + + for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) { + bbox[i].low = std::min(left_bbox[i].low, right_bbox[i].low); + bbox[i].high = std::max(left_bbox[i].high, right_bbox[i].high); + } + } + + return node; + } + + void middleSplit_(Derived &obj, IndexType *ind, IndexType count, + IndexType &index, int &cutfeat, DistanceType &cutval, + const BoundingBox &bbox) { + const DistanceType EPS = static_cast(0.00001); + ElementType max_span = bbox[0].high - bbox[0].low; + for (int i = 1; i < (DIM > 0 ? DIM : obj.dim); ++i) { + ElementType span = bbox[i].high - bbox[i].low; + if (span > max_span) { + max_span = span; + } + } + ElementType max_spread = -1; + cutfeat = 0; + for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) { + ElementType span = bbox[i].high - bbox[i].low; + if (span > (1 - EPS) * max_span) { + ElementType min_elem, max_elem; + computeMinMax(obj, ind, count, i, min_elem, max_elem); + ElementType spread = max_elem - min_elem; + if (spread > max_spread) { + cutfeat = i; + max_spread = spread; + } + } + } + // split in the middle + DistanceType split_val = (bbox[cutfeat].low + bbox[cutfeat].high) / 2; + ElementType min_elem, max_elem; + computeMinMax(obj, ind, count, cutfeat, min_elem, max_elem); + + if (split_val < min_elem) + cutval = min_elem; + else if (split_val > max_elem) + cutval = max_elem; + else + cutval = split_val; + + IndexType lim1, lim2; + planeSplit(obj, ind, count, cutfeat, cutval, lim1, lim2); + + if (lim1 > count / 2) + index = lim1; + else if (lim2 < count / 2) + index = lim2; + else + index = count / 2; + } + + /** + * Subdivide the list of points by a plane perpendicular on axe corresponding + * to the 'cutfeat' dimension at 'cutval' position. + * + * On return: + * dataset[ind[0..lim1-1]][cutfeat]cutval + */ + void planeSplit(Derived &obj, IndexType *ind, const IndexType count, + int cutfeat, DistanceType &cutval, IndexType &lim1, + IndexType &lim2) { + /* Move vector indices for left subtree to front of list. */ + IndexType left = 0; + IndexType right = count - 1; + for (;;) { + while (left <= right && dataset_get(obj, ind[left], cutfeat) < cutval) + ++left; + while (right && left <= right && + dataset_get(obj, ind[right], cutfeat) >= cutval) + --right; + if (left > right || !right) + break; // "!right" was added to support unsigned Index types + std::swap(ind[left], ind[right]); + ++left; + --right; + } + /* If either list is empty, it means that all remaining features + * are identical. Split in the middle to maintain a balanced tree. + */ + lim1 = left; + right = count - 1; + for (;;) { + while (left <= right && dataset_get(obj, ind[left], cutfeat) <= cutval) + ++left; + while (right && left <= right && + dataset_get(obj, ind[right], cutfeat) > cutval) + --right; + if (left > right || !right) + break; // "!right" was added to support unsigned Index types + std::swap(ind[left], ind[right]); + ++left; + --right; + } + lim2 = left; + } + + DistanceType computeInitialDistances(const Derived &obj, + const ElementType *vec, + distance_vector_t &dists) const { + assert(vec); + DistanceType distsq = DistanceType(); + + for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) { + if (vec[i] < obj.root_bbox[i].low) { + dists[i] = obj.distance.accum_dist(vec[i], obj.root_bbox[i].low, i); + distsq += dists[i]; + } + if (vec[i] > obj.root_bbox[i].high) { + dists[i] = obj.distance.accum_dist(vec[i], obj.root_bbox[i].high, i); + distsq += dists[i]; + } + } + return distsq; + } + + void save_tree(Derived &obj, FILE *stream, NodePtr tree) { + save_value(stream, *tree); + if (tree->child1 != NULL) { + save_tree(obj, stream, tree->child1); + } + if (tree->child2 != NULL) { + save_tree(obj, stream, tree->child2); + } + } + + void load_tree(Derived &obj, FILE *stream, NodePtr &tree) { + tree = obj.pool.template allocate(); + load_value(stream, *tree); + if (tree->child1 != NULL) { + load_tree(obj, stream, tree->child1); + } + if (tree->child2 != NULL) { + load_tree(obj, stream, tree->child2); + } + } + + /** Stores the index in a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so when + * loading the index object it must be constructed associated to the same + * source of data points used while building it. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void saveIndex_(Derived &obj, FILE *stream) { + save_value(stream, obj.m_size); + save_value(stream, obj.dim); + save_value(stream, obj.root_bbox); + save_value(stream, obj.m_leaf_max_size); + save_value(stream, obj.vind); + save_tree(obj, stream, obj.root_node); + } + + /** Loads a previous index from a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so the + * index object must be constructed associated to the same source of data + * points used while building the index. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void loadIndex_(Derived &obj, FILE *stream) { + load_value(stream, obj.m_size); + load_value(stream, obj.dim); + load_value(stream, obj.root_bbox); + load_value(stream, obj.m_leaf_max_size); + load_value(stream, obj.vind); + load_tree(obj, stream, obj.root_node); + } +}; + +/** @addtogroup kdtrees_grp KD-tree classes and adaptors + * @{ */ + +/** kd-tree static index + * + * Contains the k-d trees and other information for indexing a set of points + * for nearest-neighbor matching. + * + * The class "DatasetAdaptor" must provide the following interface (can be + * non-virtual, inlined methods): + * + * \code + * // Must return the number of data poins + * inline size_t kdtree_get_point_count() const { ... } + * + * + * // Must return the dim'th component of the idx'th point in the class: + * inline T kdtree_get_pt(const size_t idx, const size_t dim) const { ... } + * + * // Optional bounding-box computation: return false to default to a standard + * bbox computation loop. + * // Return true if the BBOX was already computed by the class and returned + * in "bb" so it can be avoided to redo it again. + * // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3 + * for point clouds) template bool kdtree_get_bbox(BBOX &bb) const + * { + * bb[0].low = ...; bb[0].high = ...; // 0th dimension limits + * bb[1].low = ...; bb[1].high = ...; // 1st dimension limits + * ... + * return true; + * } + * + * \endcode + * + * \tparam DatasetAdaptor The user-provided adaptor (see comments above). + * \tparam Distance The distance metric to use: nanoflann::metric_L1, + * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam DIM + * Dimensionality of data points (e.g. 3 for 3D points) \tparam IndexType Will + * be typically size_t or int + */ +template +class KDTreeSingleIndexAdaptor + : public KDTreeBaseClass< + KDTreeSingleIndexAdaptor, + Distance, DatasetAdaptor, DIM, IndexType> { +public: + /** Deleted copy constructor*/ + KDTreeSingleIndexAdaptor( + const KDTreeSingleIndexAdaptor + &) = delete; + + /** + * The dataset used by this index + */ + const DatasetAdaptor &dataset; //!< The source of our data + + const KDTreeSingleIndexAdaptorParams index_params; + + Distance distance; + + typedef typename nanoflann::KDTreeBaseClass< + nanoflann::KDTreeSingleIndexAdaptor, + Distance, DatasetAdaptor, DIM, IndexType> + BaseClassRef; + + typedef typename BaseClassRef::ElementType ElementType; + typedef typename BaseClassRef::DistanceType DistanceType; + + typedef typename BaseClassRef::Node Node; + typedef Node *NodePtr; + + typedef typename BaseClassRef::Interval Interval; + /** Define "BoundingBox" as a fixed-size or variable-size container depending + * on "DIM" */ + typedef typename BaseClassRef::BoundingBox BoundingBox; + + /** Define "distance_vector_t" as a fixed-size or variable-size container + * depending on "DIM" */ + typedef typename BaseClassRef::distance_vector_t distance_vector_t; + + /** + * KDTree constructor + * + * Refer to docs in README.md or online in + * https://github.com/jlblancoc/nanoflann + * + * The KD-Tree point dimension (the length of each point in the datase, e.g. 3 + * for 3D points) is determined by means of: + * - The \a DIM template parameter if >0 (highest priority) + * - Otherwise, the \a dimensionality parameter of this constructor. + * + * @param inputData Dataset with the input features + * @param params Basically, the maximum leaf node size + */ + KDTreeSingleIndexAdaptor(const int dimensionality, + const DatasetAdaptor &inputData, + const KDTreeSingleIndexAdaptorParams ¶ms = + KDTreeSingleIndexAdaptorParams()) + : dataset(inputData), index_params(params), distance(inputData) { + BaseClassRef::root_node = NULL; + BaseClassRef::m_size = dataset.kdtree_get_point_count(); + BaseClassRef::m_size_at_index_build = BaseClassRef::m_size; + BaseClassRef::dim = dimensionality; + if (DIM > 0) + BaseClassRef::dim = DIM; + BaseClassRef::m_leaf_max_size = params.leaf_max_size; + + // Create a permutable array of indices to the input vectors. + init_vind(); + } + + /** + * Builds the index + */ + void buildIndex() { + BaseClassRef::m_size = dataset.kdtree_get_point_count(); + BaseClassRef::m_size_at_index_build = BaseClassRef::m_size; + init_vind(); + this->freeIndex(*this); + BaseClassRef::m_size_at_index_build = BaseClassRef::m_size; + if (BaseClassRef::m_size == 0) + return; + computeBoundingBox(BaseClassRef::root_bbox); + BaseClassRef::root_node = + this->divideTree(*this, 0, BaseClassRef::m_size, + BaseClassRef::root_bbox); // construct the tree + } + + /** \name Query methods + * @{ */ + + /** + * Find set of nearest neighbors to vec[0:dim-1]. Their indices are stored + * inside the result object. + * + * Params: + * result = the result object in which the indices of the + * nearest-neighbors are stored vec = the vector for which to search the + * nearest neighbors + * + * \tparam RESULTSET Should be any ResultSet + * \return True if the requested neighbors could be found. + * \sa knnSearch, radiusSearch + */ + template + bool findNeighbors(RESULTSET &result, const ElementType *vec, + const SearchParams &searchParams) const { + assert(vec); + if (this->size(*this) == 0) + return false; + if (!BaseClassRef::root_node) + throw std::runtime_error( + "[nanoflann] findNeighbors() called before building the index."); + float epsError = 1 + searchParams.eps; + + distance_vector_t + dists; // fixed or variable-sized container (depending on DIM) + auto zero = static_cast(0); + assign(dists, (DIM > 0 ? DIM : BaseClassRef::dim), + zero); // Fill it with zeros. + DistanceType distsq = this->computeInitialDistances(*this, vec, dists); + searchLevel(result, vec, BaseClassRef::root_node, distsq, dists, + epsError); // "count_leaf" parameter removed since was neither + // used nor returned to the user. + return result.full(); + } + + /** + * Find the "num_closest" nearest neighbors to the \a query_point[0:dim-1]. + * Their indices are stored inside the result object. \sa radiusSearch, + * findNeighbors \note nChecks_IGNORED is ignored but kept for compatibility + * with the original FLANN interface. \return Number `N` of valid points in + * the result set. Only the first `N` entries in `out_indices` and + * `out_distances_sq` will be valid. Return may be less than `num_closest` + * only if the number of elements in the tree is less than `num_closest`. + */ + size_t knnSearch(const ElementType *query_point, const size_t num_closest, + IndexType *out_indices, DistanceType *out_distances_sq, + const int /* nChecks_IGNORED */ = 10) const { + nanoflann::KNNResultSet resultSet(num_closest); + resultSet.init(out_indices, out_distances_sq); + this->findNeighbors(resultSet, query_point, nanoflann::SearchParams()); + return resultSet.size(); + } + + /** + * Find all the neighbors to \a query_point[0:dim-1] within a maximum radius. + * The output is given as a vector of pairs, of which the first element is a + * point index and the second the corresponding distance. Previous contents of + * \a IndicesDists are cleared. + * + * If searchParams.sorted==true, the output list is sorted by ascending + * distances. + * + * For a better performance, it is advisable to do a .reserve() on the vector + * if you have any wild guess about the number of expected matches. + * + * \sa knnSearch, findNeighbors, radiusSearchCustomCallback + * \return The number of points within the given radius (i.e. indices.size() + * or dists.size() ) + */ + size_t + radiusSearch(const ElementType *query_point, const DistanceType &radius, + std::vector> &IndicesDists, + const SearchParams &searchParams) const { + RadiusResultSet resultSet(radius, IndicesDists); + const size_t nFound = + radiusSearchCustomCallback(query_point, resultSet, searchParams); + if (searchParams.sorted) + std::sort(IndicesDists.begin(), IndicesDists.end(), IndexDist_Sorter()); + return nFound; + } + + /** + * Just like radiusSearch() but with a custom callback class for each point + * found in the radius of the query. See the source of RadiusResultSet<> as a + * start point for your own classes. \sa radiusSearch + */ + template + size_t radiusSearchCustomCallback( + const ElementType *query_point, SEARCH_CALLBACK &resultSet, + const SearchParams &searchParams = SearchParams()) const { + this->findNeighbors(resultSet, query_point, searchParams); + return resultSet.size(); + } + + /** @} */ + +public: + /** Make sure the auxiliary list \a vind has the same size than the current + * dataset, and re-generate if size has changed. */ + void init_vind() { + // Create a permutable array of indices to the input vectors. + BaseClassRef::m_size = dataset.kdtree_get_point_count(); + if (BaseClassRef::vind.size() != BaseClassRef::m_size) + BaseClassRef::vind.resize(BaseClassRef::m_size); + for (size_t i = 0; i < BaseClassRef::m_size; i++) + BaseClassRef::vind[i] = i; + } + + void computeBoundingBox(BoundingBox &bbox) { + resize(bbox, (DIM > 0 ? DIM : BaseClassRef::dim)); + if (dataset.kdtree_get_bbox(bbox)) { + // Done! It was implemented in derived class + } else { + const size_t N = dataset.kdtree_get_point_count(); + if (!N) + throw std::runtime_error("[nanoflann] computeBoundingBox() called but " + "no data points found."); + for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) { + bbox[i].low = bbox[i].high = this->dataset_get(*this, 0, i); + } + for (size_t k = 1; k < N; ++k) { + for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) { + if (this->dataset_get(*this, k, i) < bbox[i].low) + bbox[i].low = this->dataset_get(*this, k, i); + if (this->dataset_get(*this, k, i) > bbox[i].high) + bbox[i].high = this->dataset_get(*this, k, i); + } + } + } + } + + /** + * Performs an exact search in the tree starting from a node. + * \tparam RESULTSET Should be any ResultSet + * \return true if the search should be continued, false if the results are + * sufficient + */ + template + bool searchLevel(RESULTSET &result_set, const ElementType *vec, + const NodePtr node, DistanceType mindistsq, + distance_vector_t &dists, const float epsError) const { + /* If this is a leaf node, then do check and return. */ + if ((node->child1 == NULL) && (node->child2 == NULL)) { + // count_leaf += (node->lr.right-node->lr.left); // Removed since was + // neither used nor returned to the user. + DistanceType worst_dist = result_set.worstDist(); + for (IndexType i = node->node_type.lr.left; i < node->node_type.lr.right; + ++i) { + const IndexType index = BaseClassRef::vind[i]; // reorder... : i; + DistanceType dist = distance.evalMetric( + vec, index, (DIM > 0 ? DIM : BaseClassRef::dim)); + if (dist < worst_dist) { + if (!result_set.addPoint(dist, BaseClassRef::vind[i])) { + // the resultset doesn't want to receive any more points, we're done + // searching! + return false; + } + } + } + return true; + } + + /* Which child branch should be taken first? */ + int idx = node->node_type.sub.divfeat; + ElementType val = vec[idx]; + DistanceType diff1 = val - node->node_type.sub.divlow; + DistanceType diff2 = val - node->node_type.sub.divhigh; + + NodePtr bestChild; + NodePtr otherChild; + DistanceType cut_dist; + if ((diff1 + diff2) < 0) { + bestChild = node->child1; + otherChild = node->child2; + cut_dist = distance.accum_dist(val, node->node_type.sub.divhigh, idx); + } else { + bestChild = node->child2; + otherChild = node->child1; + cut_dist = distance.accum_dist(val, node->node_type.sub.divlow, idx); + } + + /* Call recursively to search next level down. */ + if (!searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError)) { + // the resultset doesn't want to receive any more points, we're done + // searching! + return false; + } + + DistanceType dst = dists[idx]; + mindistsq = mindistsq + cut_dist - dst; + dists[idx] = cut_dist; + if (mindistsq * epsError <= result_set.worstDist()) { + if (!searchLevel(result_set, vec, otherChild, mindistsq, dists, + epsError)) { + // the resultset doesn't want to receive any more points, we're done + // searching! + return false; + } + } + dists[idx] = dst; + return true; + } + +public: + /** Stores the index in a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so when + * loading the index object it must be constructed associated to the same + * source of data points used while building it. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void saveIndex(FILE *stream) { this->saveIndex_(*this, stream); } + + /** Loads a previous index from a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so the + * index object must be constructed associated to the same source of data + * points used while building the index. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void loadIndex(FILE *stream) { this->loadIndex_(*this, stream); } + +}; // class KDTree + +/** kd-tree dynamic index + * + * Contains the k-d trees and other information for indexing a set of points + * for nearest-neighbor matching. + * + * The class "DatasetAdaptor" must provide the following interface (can be + * non-virtual, inlined methods): + * + * \code + * // Must return the number of data poins + * inline size_t kdtree_get_point_count() const { ... } + * + * // Must return the dim'th component of the idx'th point in the class: + * inline T kdtree_get_pt(const size_t idx, const size_t dim) const { ... } + * + * // Optional bounding-box computation: return false to default to a standard + * bbox computation loop. + * // Return true if the BBOX was already computed by the class and returned + * in "bb" so it can be avoided to redo it again. + * // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3 + * for point clouds) template bool kdtree_get_bbox(BBOX &bb) const + * { + * bb[0].low = ...; bb[0].high = ...; // 0th dimension limits + * bb[1].low = ...; bb[1].high = ...; // 1st dimension limits + * ... + * return true; + * } + * + * \endcode + * + * \tparam DatasetAdaptor The user-provided adaptor (see comments above). + * \tparam Distance The distance metric to use: nanoflann::metric_L1, + * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam DIM + * Dimensionality of data points (e.g. 3 for 3D points) \tparam IndexType Will + * be typically size_t or int + */ +template +class KDTreeSingleIndexDynamicAdaptor_ + : public KDTreeBaseClass, + Distance, DatasetAdaptor, DIM, IndexType> { +public: + /** + * The dataset used by this index + */ + const DatasetAdaptor &dataset; //!< The source of our data + + KDTreeSingleIndexAdaptorParams index_params; + + std::vector &treeIndex; + + Distance distance; + + typedef typename nanoflann::KDTreeBaseClass< + nanoflann::KDTreeSingleIndexDynamicAdaptor_, + Distance, DatasetAdaptor, DIM, IndexType> + BaseClassRef; + + typedef typename BaseClassRef::ElementType ElementType; + typedef typename BaseClassRef::DistanceType DistanceType; + + typedef typename BaseClassRef::Node Node; + typedef Node *NodePtr; + + typedef typename BaseClassRef::Interval Interval; + /** Define "BoundingBox" as a fixed-size or variable-size container depending + * on "DIM" */ + typedef typename BaseClassRef::BoundingBox BoundingBox; + + /** Define "distance_vector_t" as a fixed-size or variable-size container + * depending on "DIM" */ + typedef typename BaseClassRef::distance_vector_t distance_vector_t; + + /** + * KDTree constructor + * + * Refer to docs in README.md or online in + * https://github.com/jlblancoc/nanoflann + * + * The KD-Tree point dimension (the length of each point in the datase, e.g. 3 + * for 3D points) is determined by means of: + * - The \a DIM template parameter if >0 (highest priority) + * - Otherwise, the \a dimensionality parameter of this constructor. + * + * @param inputData Dataset with the input features + * @param params Basically, the maximum leaf node size + */ + KDTreeSingleIndexDynamicAdaptor_( + const int dimensionality, const DatasetAdaptor &inputData, + std::vector &treeIndex_, + const KDTreeSingleIndexAdaptorParams ¶ms = + KDTreeSingleIndexAdaptorParams()) + : dataset(inputData), index_params(params), treeIndex(treeIndex_), + distance(inputData) { + BaseClassRef::root_node = NULL; + BaseClassRef::m_size = 0; + BaseClassRef::m_size_at_index_build = 0; + BaseClassRef::dim = dimensionality; + if (DIM > 0) + BaseClassRef::dim = DIM; + BaseClassRef::m_leaf_max_size = params.leaf_max_size; + } + + /** Assignment operator definiton */ + KDTreeSingleIndexDynamicAdaptor_ + operator=(const KDTreeSingleIndexDynamicAdaptor_ &rhs) { + KDTreeSingleIndexDynamicAdaptor_ tmp(rhs); + std::swap(BaseClassRef::vind, tmp.BaseClassRef::vind); + std::swap(BaseClassRef::m_leaf_max_size, tmp.BaseClassRef::m_leaf_max_size); + std::swap(index_params, tmp.index_params); + std::swap(treeIndex, tmp.treeIndex); + std::swap(BaseClassRef::m_size, tmp.BaseClassRef::m_size); + std::swap(BaseClassRef::m_size_at_index_build, + tmp.BaseClassRef::m_size_at_index_build); + std::swap(BaseClassRef::root_node, tmp.BaseClassRef::root_node); + std::swap(BaseClassRef::root_bbox, tmp.BaseClassRef::root_bbox); + std::swap(BaseClassRef::pool, tmp.BaseClassRef::pool); + return *this; + } + + /** + * Builds the index + */ + void buildIndex() { + BaseClassRef::m_size = BaseClassRef::vind.size(); + this->freeIndex(*this); + BaseClassRef::m_size_at_index_build = BaseClassRef::m_size; + if (BaseClassRef::m_size == 0) + return; + computeBoundingBox(BaseClassRef::root_bbox); + BaseClassRef::root_node = + this->divideTree(*this, 0, BaseClassRef::m_size, + BaseClassRef::root_bbox); // construct the tree + } + + /** \name Query methods + * @{ */ + + /** + * Find set of nearest neighbors to vec[0:dim-1]. Their indices are stored + * inside the result object. + * + * Params: + * result = the result object in which the indices of the + * nearest-neighbors are stored vec = the vector for which to search the + * nearest neighbors + * + * \tparam RESULTSET Should be any ResultSet + * \return True if the requested neighbors could be found. + * \sa knnSearch, radiusSearch + */ + template + bool findNeighbors(RESULTSET &result, const ElementType *vec, + const SearchParams &searchParams) const { + assert(vec); + if (this->size(*this) == 0) + return false; + if (!BaseClassRef::root_node) + return false; + float epsError = 1 + searchParams.eps; + + // fixed or variable-sized container (depending on DIM) + distance_vector_t dists; + // Fill it with zeros. + assign(dists, (DIM > 0 ? DIM : BaseClassRef::dim), + static_cast(0)); + DistanceType distsq = this->computeInitialDistances(*this, vec, dists); + searchLevel(result, vec, BaseClassRef::root_node, distsq, dists, + epsError); // "count_leaf" parameter removed since was neither + // used nor returned to the user. + return result.full(); + } + + /** + * Find the "num_closest" nearest neighbors to the \a query_point[0:dim-1]. + * Their indices are stored inside the result object. \sa radiusSearch, + * findNeighbors \note nChecks_IGNORED is ignored but kept for compatibility + * with the original FLANN interface. \return Number `N` of valid points in + * the result set. Only the first `N` entries in `out_indices` and + * `out_distances_sq` will be valid. Return may be less than `num_closest` + * only if the number of elements in the tree is less than `num_closest`. + */ + size_t knnSearch(const ElementType *query_point, const size_t num_closest, + IndexType *out_indices, DistanceType *out_distances_sq, + const int /* nChecks_IGNORED */ = 10) const { + nanoflann::KNNResultSet resultSet(num_closest); + resultSet.init(out_indices, out_distances_sq); + this->findNeighbors(resultSet, query_point, nanoflann::SearchParams()); + return resultSet.size(); + } + + /** + * Find all the neighbors to \a query_point[0:dim-1] within a maximum radius. + * The output is given as a vector of pairs, of which the first element is a + * point index and the second the corresponding distance. Previous contents of + * \a IndicesDists are cleared. + * + * If searchParams.sorted==true, the output list is sorted by ascending + * distances. + * + * For a better performance, it is advisable to do a .reserve() on the vector + * if you have any wild guess about the number of expected matches. + * + * \sa knnSearch, findNeighbors, radiusSearchCustomCallback + * \return The number of points within the given radius (i.e. indices.size() + * or dists.size() ) + */ + size_t + radiusSearch(const ElementType *query_point, const DistanceType &radius, + std::vector> &IndicesDists, + const SearchParams &searchParams) const { + RadiusResultSet resultSet(radius, IndicesDists); + const size_t nFound = + radiusSearchCustomCallback(query_point, resultSet, searchParams); + if (searchParams.sorted) + std::sort(IndicesDists.begin(), IndicesDists.end(), IndexDist_Sorter()); + return nFound; + } + + /** + * Just like radiusSearch() but with a custom callback class for each point + * found in the radius of the query. See the source of RadiusResultSet<> as a + * start point for your own classes. \sa radiusSearch + */ + template + size_t radiusSearchCustomCallback( + const ElementType *query_point, SEARCH_CALLBACK &resultSet, + const SearchParams &searchParams = SearchParams()) const { + this->findNeighbors(resultSet, query_point, searchParams); + return resultSet.size(); + } + + /** @} */ + +public: + void computeBoundingBox(BoundingBox &bbox) { + resize(bbox, (DIM > 0 ? DIM : BaseClassRef::dim)); + + if (dataset.kdtree_get_bbox(bbox)) { + // Done! It was implemented in derived class + } else { + const size_t N = BaseClassRef::m_size; + if (!N) + throw std::runtime_error("[nanoflann] computeBoundingBox() called but " + "no data points found."); + for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) { + bbox[i].low = bbox[i].high = + this->dataset_get(*this, BaseClassRef::vind[0], i); + } + for (size_t k = 1; k < N; ++k) { + for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) { + if (this->dataset_get(*this, BaseClassRef::vind[k], i) < bbox[i].low) + bbox[i].low = this->dataset_get(*this, BaseClassRef::vind[k], i); + if (this->dataset_get(*this, BaseClassRef::vind[k], i) > bbox[i].high) + bbox[i].high = this->dataset_get(*this, BaseClassRef::vind[k], i); + } + } + } + } + + /** + * Performs an exact search in the tree starting from a node. + * \tparam RESULTSET Should be any ResultSet + */ + template + void searchLevel(RESULTSET &result_set, const ElementType *vec, + const NodePtr node, DistanceType mindistsq, + distance_vector_t &dists, const float epsError) const { + /* If this is a leaf node, then do check and return. */ + if ((node->child1 == NULL) && (node->child2 == NULL)) { + // count_leaf += (node->lr.right-node->lr.left); // Removed since was + // neither used nor returned to the user. + DistanceType worst_dist = result_set.worstDist(); + for (IndexType i = node->node_type.lr.left; i < node->node_type.lr.right; + ++i) { + const IndexType index = BaseClassRef::vind[i]; // reorder... : i; + if (treeIndex[index] == -1) + continue; + DistanceType dist = distance.evalMetric( + vec, index, (DIM > 0 ? DIM : BaseClassRef::dim)); + if (dist < worst_dist) { + if (!result_set.addPoint( + static_cast(dist), + static_cast( + BaseClassRef::vind[i]))) { + // the resultset doesn't want to receive any more points, we're done + // searching! + return; // false; + } + } + } + return; + } + + /* Which child branch should be taken first? */ + int idx = node->node_type.sub.divfeat; + ElementType val = vec[idx]; + DistanceType diff1 = val - node->node_type.sub.divlow; + DistanceType diff2 = val - node->node_type.sub.divhigh; + + NodePtr bestChild; + NodePtr otherChild; + DistanceType cut_dist; + if ((diff1 + diff2) < 0) { + bestChild = node->child1; + otherChild = node->child2; + cut_dist = distance.accum_dist(val, node->node_type.sub.divhigh, idx); + } else { + bestChild = node->child2; + otherChild = node->child1; + cut_dist = distance.accum_dist(val, node->node_type.sub.divlow, idx); + } + + /* Call recursively to search next level down. */ + searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError); + + DistanceType dst = dists[idx]; + mindistsq = mindistsq + cut_dist - dst; + dists[idx] = cut_dist; + if (mindistsq * epsError <= result_set.worstDist()) { + searchLevel(result_set, vec, otherChild, mindistsq, dists, epsError); + } + dists[idx] = dst; + } + +public: + /** Stores the index in a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so when + * loading the index object it must be constructed associated to the same + * source of data points used while building it. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void saveIndex(FILE *stream) { this->saveIndex_(*this, stream); } + + /** Loads a previous index from a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so the + * index object must be constructed associated to the same source of data + * points used while building the index. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void loadIndex(FILE *stream) { this->loadIndex_(*this, stream); } +}; + +/** kd-tree dynaimic index + * + * class to create multiple static index and merge their results to behave as + * single dynamic index as proposed in Logarithmic Approach. + * + * Example of usage: + * examples/dynamic_pointcloud_example.cpp + * + * \tparam DatasetAdaptor The user-provided adaptor (see comments above). + * \tparam Distance The distance metric to use: nanoflann::metric_L1, + * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam DIM + * Dimensionality of data points (e.g. 3 for 3D points) \tparam IndexType Will + * be typically size_t or int + */ +template +class KDTreeSingleIndexDynamicAdaptor { +public: + typedef typename Distance::ElementType ElementType; + typedef typename Distance::DistanceType DistanceType; + +protected: + size_t m_leaf_max_size; + size_t treeCount; + size_t pointCount; + + /** + * The dataset used by this index + */ + const DatasetAdaptor &dataset; //!< The source of our data + + std::vector treeIndex; //!< treeIndex[idx] is the index of tree in which + //!< point at idx is stored. treeIndex[idx]=-1 + //!< means that point has been removed. + + KDTreeSingleIndexAdaptorParams index_params; + + int dim; //!< Dimensionality of each data point + + typedef KDTreeSingleIndexDynamicAdaptor_ + index_container_t; + std::vector index; + +public: + /** Get a const ref to the internal list of indices; the number of indices is + * adapted dynamically as the dataset grows in size. */ + const std::vector &getAllIndices() const { return index; } + +private: + /** finds position of least significant unset bit */ + int First0Bit(IndexType num) { + int pos = 0; + while (num & 1) { + num = num >> 1; + pos++; + } + return pos; + } + + /** Creates multiple empty trees to handle dynamic support */ + void init() { + typedef KDTreeSingleIndexDynamicAdaptor_ + my_kd_tree_t; + std::vector index_( + treeCount, my_kd_tree_t(dim /*dim*/, dataset, treeIndex, index_params)); + index = index_; + } + +public: + Distance distance; + + /** + * KDTree constructor + * + * Refer to docs in README.md or online in + * https://github.com/jlblancoc/nanoflann + * + * The KD-Tree point dimension (the length of each point in the datase, e.g. 3 + * for 3D points) is determined by means of: + * - The \a DIM template parameter if >0 (highest priority) + * - Otherwise, the \a dimensionality parameter of this constructor. + * + * @param inputData Dataset with the input features + * @param params Basically, the maximum leaf node size + */ + KDTreeSingleIndexDynamicAdaptor(const int dimensionality, + const DatasetAdaptor &inputData, + const KDTreeSingleIndexAdaptorParams ¶ms = + KDTreeSingleIndexAdaptorParams(), + const size_t maximumPointCount = 1000000000U) + : dataset(inputData), index_params(params), distance(inputData) { + treeCount = static_cast(std::log2(maximumPointCount)); + pointCount = 0U; + dim = dimensionality; + treeIndex.clear(); + if (DIM > 0) + dim = DIM; + m_leaf_max_size = params.leaf_max_size; + init(); + const size_t num_initial_points = dataset.kdtree_get_point_count(); + if (num_initial_points > 0) { + addPoints(0, num_initial_points - 1); + } + } + + /** Deleted copy constructor*/ + KDTreeSingleIndexDynamicAdaptor( + const KDTreeSingleIndexDynamicAdaptor &) = delete; + + /** Add points to the set, Inserts all points from [start, end] */ + void addPoints(IndexType start, IndexType end) { + size_t count = end - start + 1; + treeIndex.resize(treeIndex.size() + count); + for (IndexType idx = start; idx <= end; idx++) { + int pos = First0Bit(pointCount); + index[pos].vind.clear(); + treeIndex[pointCount] = pos; + for (int i = 0; i < pos; i++) { + for (int j = 0; j < static_cast(index[i].vind.size()); j++) { + index[pos].vind.push_back(index[i].vind[j]); + if (treeIndex[index[i].vind[j]] != -1) + treeIndex[index[i].vind[j]] = pos; + } + index[i].vind.clear(); + index[i].freeIndex(index[i]); + } + index[pos].vind.push_back(idx); + index[pos].buildIndex(); + pointCount++; + } + } + + /** Remove a point from the set (Lazy Deletion) */ + void removePoint(size_t idx) { + if (idx >= pointCount) + return; + treeIndex[idx] = -1; + } + + /** + * Find set of nearest neighbors to vec[0:dim-1]. Their indices are stored + * inside the result object. + * + * Params: + * result = the result object in which the indices of the + * nearest-neighbors are stored vec = the vector for which to search the + * nearest neighbors + * + * \tparam RESULTSET Should be any ResultSet + * \return True if the requested neighbors could be found. + * \sa knnSearch, radiusSearch + */ + template + bool findNeighbors(RESULTSET &result, const ElementType *vec, + const SearchParams &searchParams) const { + for (size_t i = 0; i < treeCount; i++) { + index[i].findNeighbors(result, &vec[0], searchParams); + } + return result.full(); + } +}; + +/** An L2-metric KD-tree adaptor for working with data directly stored in an + * Eigen Matrix, without duplicating the data storage. You can select whether a + * row or column in the matrix represents a point in the state space. + * + * Example of usage: + * \code + * Eigen::Matrix mat; + * // Fill out "mat"... + * + * typedef KDTreeEigenMatrixAdaptor< Eigen::Matrix > + * my_kd_tree_t; const int max_leaf = 10; my_kd_tree_t mat_index(mat, max_leaf + * ); mat_index.index->buildIndex(); mat_index.index->... \endcode + * + * \tparam DIM If set to >0, it specifies a compile-time fixed dimensionality + * for the points in the data set, allowing more compiler optimizations. \tparam + * Distance The distance metric to use: nanoflann::metric_L1, + * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam row_major + * If set to true the rows of the matrix are used as the points, if set to false + * the columns of the matrix are used as the points. + */ +template +struct KDTreeEigenMatrixAdaptor { + typedef KDTreeEigenMatrixAdaptor self_t; + typedef typename MatrixType::Scalar num_t; + typedef typename MatrixType::Index IndexType; + typedef + typename Distance::template traits::distance_t metric_t; + typedef KDTreeSingleIndexAdaptor + index_t; + + index_t *index; //! The kd-tree index for the user to call its methods as + //! usual with any other FLANN index. + + /// Constructor: takes a const ref to the matrix object with the data points + KDTreeEigenMatrixAdaptor(const size_t dimensionality, + const std::reference_wrapper &mat, + const int leaf_max_size = 10) + : m_data_matrix(mat) { + const auto dims = row_major ? mat.get().cols() : mat.get().rows(); + if (size_t(dims) != dimensionality) + throw std::runtime_error( + "Error: 'dimensionality' must match column count in data matrix"); + if (DIM > 0 && int(dims) != DIM) + throw std::runtime_error( + "Data set dimensionality does not match the 'DIM' template argument"); + index = + new index_t(static_cast(dims), *this /* adaptor */, + nanoflann::KDTreeSingleIndexAdaptorParams(leaf_max_size)); + index->buildIndex(); + } + +public: + /** Deleted copy constructor */ + KDTreeEigenMatrixAdaptor(const self_t &) = delete; + + ~KDTreeEigenMatrixAdaptor() { delete index; } + + const std::reference_wrapper m_data_matrix; + + /** Query for the \a num_closest closest points to a given point (entered as + * query_point[0:dim-1]). Note that this is a short-cut method for + * index->findNeighbors(). The user can also call index->... methods as + * desired. \note nChecks_IGNORED is ignored but kept for compatibility with + * the original FLANN interface. + */ + inline void query(const num_t *query_point, const size_t num_closest, + IndexType *out_indices, num_t *out_distances_sq, + const int /* nChecks_IGNORED */ = 10) const { + nanoflann::KNNResultSet resultSet(num_closest); + resultSet.init(out_indices, out_distances_sq); + index->findNeighbors(resultSet, query_point, nanoflann::SearchParams()); + } + + /** @name Interface expected by KDTreeSingleIndexAdaptor + * @{ */ + + const self_t &derived() const { return *this; } + self_t &derived() { return *this; } + + // Must return the number of data points + inline size_t kdtree_get_point_count() const { + if(row_major) + return m_data_matrix.get().rows(); + else + return m_data_matrix.get().cols(); + } + + // Returns the dim'th component of the idx'th point in the class: + inline num_t kdtree_get_pt(const IndexType idx, size_t dim) const { + if(row_major) + return m_data_matrix.get().coeff(idx, IndexType(dim)); + else + return m_data_matrix.get().coeff(IndexType(dim), idx); + } + + // Optional bounding-box computation: return false to default to a standard + // bbox computation loop. + // Return true if the BBOX was already computed by the class and returned in + // "bb" so it can be avoided to redo it again. Look at bb.size() to find out + // the expected dimensionality (e.g. 2 or 3 for point clouds) + template bool kdtree_get_bbox(BBOX & /*bb*/) const { + return false; + } + + /** @} */ + +}; // end of KDTreeEigenMatrixAdaptor + /** @} */ + +/** @} */ // end of grouping +} // namespace nanoflann + +#endif /* NANOFLANN_HPP_ */ diff --git a/trlo/include/nano_gicp/lsq_registration.hpp b/trlo/include/nano_gicp/lsq_registration.hpp new file mode 100644 index 0000000..6f88061 --- /dev/null +++ b/trlo/include/nano_gicp/lsq_registration.hpp @@ -0,0 +1,119 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * BSD 3-Clause License + * + * Copyright (c) 2020, SMRT-AIST + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +#ifndef NANO_GICP_LSQ_REGISTRATION_HPP +#define NANO_GICP_LSQ_REGISTRATION_HPP + +#include +#include + +#include +#include +#include + +namespace nano_gicp { + +enum class LSQ_OPTIMIZER_TYPE { GaussNewton, LevenbergMarquardt }; + +template +class LsqRegistration : public pcl::Registration { +public: + using Scalar = float; + using Matrix4 = typename pcl::Registration::Matrix4; + + using PointCloudSource = typename pcl::Registration::PointCloudSource; + using PointCloudSourcePtr = typename PointCloudSource::Ptr; + using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr; + + using PointCloudTarget = typename pcl::Registration::PointCloudTarget; + using PointCloudTargetPtr = typename PointCloudTarget::Ptr; + using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr; + +protected: + using pcl::Registration::input_; + using pcl::Registration::nr_iterations_; + using pcl::Registration::max_iterations_; + using pcl::Registration::final_transformation_; + using pcl::Registration::transformation_epsilon_; + using pcl::Registration::converged_; + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + LsqRegistration(); + virtual ~LsqRegistration(); + + void setRotationEpsilon(double eps); + void setInitialLambdaFactor(double init_lambda_factor); + void setDebugPrint(bool lm_debug_print); + + const Eigen::Matrix& getFinalHessian() const; + + virtual void swapSourceAndTarget() {} + virtual void clearSource() {} + virtual void clearTarget() {} + +protected: + virtual void computeTransformation(PointCloudSource& output, const Matrix4& guess) override; + + bool is_converged(const Eigen::Isometry3d& delta) const; + + virtual double linearize(const Eigen::Isometry3d& trans, Eigen::Matrix* H = nullptr, Eigen::Matrix* b = nullptr) = 0; + virtual double compute_error(const Eigen::Isometry3d& trans) = 0; + + bool step_optimize(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta); + bool step_gn(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta); + bool step_lm(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta); + +protected: + double rotation_epsilon_; + + LSQ_OPTIMIZER_TYPE lsq_optimizer_type_; + int lm_max_iterations_; + double lm_init_lambda_factor_; + double lm_lambda_; + bool lm_debug_print_; + + Eigen::Matrix final_hessian_; +}; +} // namespace nano_gicp + +#endif \ No newline at end of file diff --git a/trlo/include/nano_gicp/nano_gicp.hpp b/trlo/include/nano_gicp/nano_gicp.hpp new file mode 100644 index 0000000..6caed8f --- /dev/null +++ b/trlo/include/nano_gicp/nano_gicp.hpp @@ -0,0 +1,140 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * BSD 3-Clause License + * + * Copyright (c) 2020, SMRT-AIST + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +#ifndef NANO_GICP_NANO_GICP_HPP +#define NANO_GICP_NANO_GICP_HPP + +#include +#include + +#include +#include +#include + +#include +#include +#include + +namespace nano_gicp { + +template +class NanoGICP : public LsqRegistration { +public: + using Scalar = float; + using Matrix4 = typename pcl::Registration::Matrix4; + + using PointCloudSource = typename pcl::Registration::PointCloudSource; + using PointCloudSourcePtr = typename PointCloudSource::Ptr; + using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr; + + using PointCloudTarget = typename pcl::Registration::PointCloudTarget; + using PointCloudTargetPtr = typename PointCloudTarget::Ptr; + using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr; + +protected: + using pcl::Registration::reg_name_; + using pcl::Registration::input_; + using pcl::Registration::target_; + using pcl::Registration::corr_dist_threshold_; + +public: + NanoGICP(); + virtual ~NanoGICP() override; + + void setNumThreads(int n); + void setCorrespondenceRandomness(int k); + void setRegularizationMethod(RegularizationMethod method); + + virtual void swapSourceAndTarget() override; + virtual void clearSource() override; + virtual void clearTarget() override; + + virtual void setInputSource(const PointCloudSourceConstPtr& cloud) override; + virtual void setSourceCovariances(const std::vector>& covs); + virtual void setInputTarget(const PointCloudTargetConstPtr& cloud) override; + virtual void setTargetCovariances(const std::vector>& covs); + + virtual void registerInputSource(const PointCloudSourceConstPtr& cloud); + + virtual bool calculateSourceCovariances(); + virtual bool calculateTargetCovariances(); + + const std::vector>& getSourceCovariances() const { + return source_covs_; + } + + const std::vector>& getTargetCovariances() const { + return target_covs_; + } + +protected: + virtual void computeTransformation(PointCloudSource& output, const Matrix4& guess) override; + + virtual void update_correspondences(const Eigen::Isometry3d& trans); + + virtual double linearize(const Eigen::Isometry3d& trans, Eigen::Matrix* H, Eigen::Matrix* b) override; + + virtual double compute_error(const Eigen::Isometry3d& trans) override; + + template + bool calculate_covariances(const typename pcl::PointCloud::ConstPtr& cloud, nanoflann::KdTreeFLANN& kdtree, std::vector>& covariances); + +public: + std::shared_ptr> source_kdtree_; + std::shared_ptr> target_kdtree_; + + std::vector> source_covs_; + std::vector> target_covs_; + +protected: + int num_threads_; + int k_correspondences_; + + RegularizationMethod regularization_method_; + + std::vector> mahalanobis_; + + std::vector correspondences_; + std::vector sq_distances_; +}; +} // namespace nano_gicp + +#endif diff --git a/trlo/include/nano_gicp/nanoflann.hpp b/trlo/include/nano_gicp/nanoflann.hpp new file mode 100644 index 0000000..ebaf77a --- /dev/null +++ b/trlo/include/nano_gicp/nanoflann.hpp @@ -0,0 +1,196 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * Software License Agreement (BSD License) + * + * Copyright 2008-2009 Marius Muja (mariusm@cs.ubc.ca). All rights reserved. + * Copyright 2008-2009 David G. Lowe (lowe@cs.ubc.ca). All rights reserved. + * Copyright 2011-2021 Jose Luis Blanco (joseluisblancoc@gmail.com). + * All rights reserved. + * + * THE BSD LICENSE + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES + * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. + * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, + * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY + * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF + * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +#ifndef NANO_KDTREE_KDTREE_FLANN_H_ +#define NANO_KDTREE_KDTREE_FLANN_H_ + +#include +#include +#include +#include +#include "nano_gicp/impl/nanoflann_impl.hpp" + +namespace nanoflann +{ + +template +class KdTreeFLANN +{ +public: + + typedef typename pcl::PointCloud PointCloud; + typedef typename pcl::PointCloud::Ptr PointCloudPtr; + typedef typename pcl::PointCloud::ConstPtr PointCloudConstPtr; + + typedef boost::shared_ptr> Ptr; + typedef boost::shared_ptr> ConstPtr; + typedef boost::shared_ptr> IndicesPtr; + typedef boost::shared_ptr> IndicesConstPtr; + + KdTreeFLANN (bool sorted = false); + KdTreeFLANN (const KdTreeFLANN &k); + + void setEpsilon (float eps); + + void setSortedResults (bool sorted); + + inline Ptr makeShared () { return Ptr (new KdTreeFLANN (*this)); } + + void setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ()); + + inline PointCloudConstPtr getInputCloud() const { return _adaptor.pcl; } + + int nearestKSearch (const PointT &point, int k, std::vector &k_indices, + std::vector &k_sqr_distances) const; + + int radiusSearch (const PointT &point, double radius, std::vector &k_indices, + std::vector &k_sqr_distances) const; + +protected: + + nanoflann::SearchParams _params; + + struct PointCloud_Adaptor + { + inline size_t kdtree_get_point_count() const; + inline float kdtree_get_pt(const size_t idx, int dim) const; + template bool kdtree_get_bbox(BBOX&) const { return false; } + PointCloudConstPtr pcl; + IndicesConstPtr indices; + }; + + typedef nanoflann::KDTreeSingleIndexAdaptor< + nanoflann::SO3_Adaptor , + PointCloud_Adaptor, 3, int> KDTreeFlann_PCL_SO3; + + PointCloud_Adaptor _adaptor; + + KDTreeFlann_PCL_SO3 _kdtree; + +}; + +//---------- Definitions --------------------- + +template inline +KdTreeFLANN::KdTreeFLANN(bool sorted): + _kdtree(3,_adaptor, KDTreeSingleIndexAdaptorParams(100)) +{ + _params.sorted = sorted; +} + +template inline +void KdTreeFLANN::setEpsilon(float eps) +{ + _params.eps = eps; +} + +template inline +void KdTreeFLANN::setSortedResults(bool sorted) +{ + _params.sorted = sorted; +} + +template inline +void KdTreeFLANN::setInputCloud(const KdTreeFLANN::PointCloudConstPtr &cloud, + const IndicesConstPtr &indices) +{ + _adaptor.pcl = cloud; + _adaptor.indices = indices; + _kdtree.buildIndex(); +} + +template inline +int KdTreeFLANN::nearestKSearch(const PointT &point, int num_closest, + std::vector &k_indices, + std::vector &k_sqr_distances) const +{ + k_indices.resize(num_closest); + k_sqr_distances.resize(num_closest); + + nanoflann::KNNResultSet resultSet(num_closest); + resultSet.init( k_indices.data(), k_sqr_distances.data()); + _kdtree.findNeighbors(resultSet, point.data, nanoflann::SearchParams() ); + return resultSet.size(); +} + +template inline +int KdTreeFLANN::radiusSearch(const PointT &point, double radius, + std::vector &k_indices, + std::vector &k_sqr_distances) const +{ + static std::vector > indices_dist; + indices_dist.reserve( 128 ); + + RadiusResultSet resultSet(radius, indices_dist); + const size_t nFound = _kdtree.findNeighbors(resultSet, point.data, _params); + + if (_params.sorted) + std::sort(indices_dist.begin(), indices_dist.end(), IndexDist_Sorter() ); + + k_indices.resize(nFound); + k_sqr_distances.resize(nFound); + for(int i=0; i inline +size_t KdTreeFLANN::PointCloud_Adaptor::kdtree_get_point_count() const { + if( indices ) return indices->size(); + if( pcl) return pcl->points.size(); + return 0; +} + +template inline +float KdTreeFLANN::PointCloud_Adaptor::kdtree_get_pt(const size_t idx, int dim) const{ + const PointT& p = ( indices ) ? pcl->points[(*indices)[idx]] : pcl->points[idx]; + if (dim==0) return p.x; + else if (dim==1) return p.y; + else if (dim==2) return p.z; + else return 0.0; +} + +} + + +#endif diff --git a/trlo/include/trlo/map.h b/trlo/include/trlo/map.h new file mode 100644 index 0000000..af2c7e0 --- /dev/null +++ b/trlo/include/trlo/map.h @@ -0,0 +1,59 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +#include "trlo/trlo.h" + +class trlo::MapNode { + +public: + + MapNode(ros::NodeHandle node_handle); + ~MapNode(); + + static void abort() { + abort_ = true; + } + + void start(); + void stop(); + +private: + + void abortTimerCB(const ros::TimerEvent& e); + void publishTimerCB(const ros::TimerEvent& e); + + void keyframeCB(const sensor_msgs::PointCloud2ConstPtr& keyframe); + + bool savePcd(trlo::save_pcd::Request& req, + trlo::save_pcd::Response& res); + + void getParams(); + + ros::NodeHandle nh; + ros::Timer abort_timer; + ros::Timer publish_timer; + + ros::Subscriber keyframe_sub; + ros::Publisher map_pub; + + ros::ServiceServer save_pcd_srv; + + pcl::PointCloud::Ptr trlo_map; + pcl::VoxelGrid voxelgrid; + + ros::Time map_stamp; + std::string odom_frame; + + bool publish_full_map_; + double publish_freq_; + double leaf_size_; + + static std::atomic abort_; + +}; diff --git a/trlo/include/trlo/odom.h b/trlo/include/trlo/odom.h new file mode 100644 index 0000000..92c297e --- /dev/null +++ b/trlo/include/trlo/odom.h @@ -0,0 +1,273 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +#include "trlo/trlo.h" + +class trlo::OdomNode { + +public: + + OdomNode(ros::NodeHandle node_handle); + ~OdomNode(); + + static void abort() { + abort_ = true; + } + + void start(); + void stop(); + +private: + + void abortTimerCB(const ros::TimerEvent& e); + void icpCB(const sensor_msgs::PointCloud2ConstPtr& pc); + void imuCB(const sensor_msgs::Imu::ConstPtr& imu); + void boxCB(const jsk_recognition_msgs::BoundingBoxArrayPtr& box); + bool saveTrajectory(trlo::save_traj::Request& req, + trlo::save_traj::Response& res); + + void getParams(); + void InitParam(); + void allocateMemory(); + + void publishToROS(); + void publishPose(); + void publishTrajectory(); + void publishTransform(); + void publishKeyframe(); + void publishRobot(); + + void preprocessPoints(); + void removeClosedPointCloud(const pcl::PointCloud &cloud_in, pcl::PointCloud &cloud_out, float th1, float th2); + void initializeInputTarget(); + void setInputSources(); + + void initializeTRLO(); + void gravityAlign(); + + void getNextPose(); + void integrateIMU(); + + void propagateS2S(Eigen::Matrix4f T); + void propagateS2M(); + + void setAdaptiveParams(); + + void computeMetrics(); + void computeSpaciousness(); + + void transformCurrentScan(); + void updateKeyframes(); + void computeConvexHull(); + void computeConcaveHull(); + void pushSubmapIndices(std::vector dists, int k, std::vector frames); + void getSubmapKeyframes(); + + void debug(); + + double first_imu_time; + + ros::NodeHandle nh; + ros::Timer abort_timer; + + ros::ServiceServer save_traj_srv; + + ros::Subscriber icp_sub; + ros::Subscriber imu_sub; + ros::Subscriber box_sub; + + ros::Publisher odom_pub; + ros::Publisher trajectory_pub; + ros::Publisher pose_pub; + ros::Publisher keyframe_pub; + ros::Publisher kf_pub; + ros::Publisher robot_pub; + + Eigen::Vector3f origin; + std::vector> trajectory; + std::vector, pcl::PointCloud::Ptr>> keyframes; + std::vector>> keyframe_normals; + + std::atomic trlo_initialized; + std::atomic imu_calibrated; + + std::string odom_frame; + std::string child_frame; + + pcl::PointCloud::Ptr current_scan; + pcl::PointCloud::Ptr current_scan_t; + + pcl::PointCloud::Ptr keyframes_cloud; + pcl::PointCloud::Ptr keyframe_cloud; + int num_keyframes; + + pcl::ConvexHull convex_hull; + pcl::ConcaveHull concave_hull; + std::vector keyframe_convex; + std::vector keyframe_concave; + + pcl::PointCloud::Ptr submap_cloud; + std::vector> submap_normals; + + std::vector submap_kf_idx_curr; + std::vector submap_kf_idx_prev; + std::atomic submap_hasChanged; + std::unordered_set submap_kf_idx_hash; + + pcl::PointCloud::Ptr source_cloud; + pcl::PointCloud::Ptr target_cloud; + + ros::Time scan_stamp; + + double curr_frame_stamp; + double prev_frame_stamp; + std::vector comp_times; + std::vector submap_build_times; + std::vector ground_optimize_times; + + nano_gicp::NanoGICP gicp_s2s; + nano_gicp::NanoGICP gicp; + + pcl::CropBox crop; + pcl::VoxelGrid vf_scan; + pcl::VoxelGrid vf_submap; + + nav_msgs::Odometry odom; + nav_msgs::Odometry kf; + + geometry_msgs::PoseStamped pose_ros; + + Eigen::Matrix4f T, T_S2S_pre; + Eigen::Matrix4f T_s2s, T_s2s_prev; + + Eigen::Vector3f pose_s2s; + Eigen::Matrix3f rotSO3_s2s; + Eigen::Quaternionf rotq_s2s; + + Eigen::Vector3f pose; + Eigen::Matrix3f rotSO3; + Eigen::Quaternionf rotq; + + Eigen::Matrix4f imu_SE3; + + struct XYZd { + double x; + double y; + double z; + }; + + struct ImuBias { + XYZd gyro; + XYZd accel; + }; + + ImuBias imu_bias; + + struct ImuMeas { + double stamp; + XYZd ang_vel; + XYZd lin_accel; + }; + + ImuMeas imu_meas; + + boost::circular_buffer imu_buffer; + boost::circular_buffer box_buffer; + + static bool comparatorImu(ImuMeas m1, ImuMeas m2) { + return (m1.stamp < m2.stamp); + }; + + struct Metrics { + std::vector spaciousness; + }; + + Metrics metrics; + + static std::atomic abort_; + std::atomic stop_publish_thread; + std::atomic stop_publish_keyframe_thread; + std::atomic stop_metrics_thread; + std::atomic stop_debug_thread; + + std::thread publish_thread; + std::thread publish_keyframe_thread; + std::thread metrics_thread; + std::thread debug_thread; + + std::mutex mtx_imu; + std::mutex mtx_box; + + std::string cpu_type; + std::vector cpu_percents; + clock_t lastCPU, lastSysCPU, lastUserCPU; + int numProcessors; + + // Parameters + std::string version_; + + bool gravity_align_; + + double keyframe_thresh_dist_; + double keyframe_thresh_rot_; + + int submap_knn_; + int submap_kcv_; + int submap_kcc_; + double submap_concave_alpha_; + + bool initial_pose_use_; + Eigen::Vector3f initial_position_; + Eigen::Quaternionf initial_orientation_; + + bool crop_use_; + double crop_size_; + + bool vf_scan_use_; + double vf_scan_res_; + + bool vf_submap_use_; + double vf_submap_res_; + + bool adaptive_params_use_; + + bool imu_use_; + int imu_calib_time_; + int imu_buffer_size_; + + int box_buffer_size_; + + int gicp_min_num_points_; + + int gicps2s_k_correspondences_; + double gicps2s_max_corr_dist_; + int gicps2s_max_iter_; + double gicps2s_transformation_ep_; + double gicps2s_euclidean_fitness_ep_; + int gicps2s_ransac_iter_; + double gicps2s_ransac_inlier_thresh_; + + int gicps2m_k_correspondences_; + double gicps2m_max_corr_dist_; + int gicps2m_max_iter_; + double gicps2m_transformation_ep_; + double gicps2m_euclidean_fitness_ep_; + int gicps2m_ransac_iter_; + double gicps2m_ransac_inlier_thresh_; + + nav_msgs::Path robot_trajectory; + + bool ground_use_; + double para_tz[1] = {0}; + double para_tz_pre = 0; + double para_q[4] = {0, 0, 0, 1}; + + Eigen::Vector3f ground_normal; + double ground_threshold_; +}; diff --git a/trlo/include/trlo/trlo.h b/trlo/include/trlo/trlo.h new file mode 100644 index 0000000..11fd7f3 --- /dev/null +++ b/trlo/include/trlo/trlo.h @@ -0,0 +1,75 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +#ifdef HAS_CPUID +#include +#endif + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include + +#include "center_pointpillars/postprocess.h" + +typedef pcl::PointXYZI PointType; + +namespace trlo { + + class OdomNode; + class MapNode; + +} diff --git a/trlo/launch/trlo.launch b/trlo/launch/trlo.launch new file mode 100644 index 0000000..9cc39ec --- /dev/null +++ b/trlo/launch/trlo.launch @@ -0,0 +1,107 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/trlo/launch/trlo.rviz b/trlo/launch/trlo.rviz new file mode 100644 index 0000000..6f21088 --- /dev/null +++ b/trlo/launch/trlo.rviz @@ -0,0 +1,402 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Point_raw1/Autocompute Value Bounds1 + - /Odometry1/Shape1 + - /Keyframes1/Shape1 + - /Map1/Autocompute Value Bounds1 + Splitter Ratio: 0.5382353067398071 + Tree Height: 892 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.4960629940032959 + - Class: rviz/Time + Name: Time + SyncMode: 0 + SyncSource: Map +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.25 + Cell Size: 1 + Class: rviz/Grid + Color: 100; 100; 100 + Enabled: false + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 1000 + Reference Frame: robot/odom + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 6 + Min Value: -2 + Value: false + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: Point_raw + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 1 + Size (m): 0.10000000149011612 + Style: Points + Topic: /robot/cpp/centerpp_node/pointcloud_raw + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Angle Tolerance: 0.009999999776482582 + Class: rviz/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: false + Enabled: true + Keep: 1 + Name: Odometry + Position Tolerance: 0.009999999776482582 + Queue Size: 1000 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.25 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Axes + Topic: /robot/trlo/odom_node/odom + Unreliable: false + Value: true + - Angle Tolerance: 0.10000000149011612 + Class: rviz/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: false + Enabled: true + Keep: 1000 + Name: Keyframes + Position Tolerance: 0.10000000149011612 + Queue Size: 1000 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.20000000298023224 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Axes + Topic: /robot/trlo/odom_node/odom/keyframe + Unreliable: false + Value: true + - Alpha: 0.10000000149011612 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 2 + Min Value: -2 + Value: false + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 211; 215; 207 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 0; 0; 0 + Min Color: 255; 255; 255 + Name: Map + Position Transformer: XYZ + Queue Size: 1000 + Selectable: true + Size (Pixels): 2 + Size (m): 0.10000000149011612 + Style: Points + Topic: /robot/trlo/map_node/map + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /robot/trlo/odom_node/trajectory + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: Point_static + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /robot/cpp/centerpp_node/pointcloud_static + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: jsk_rviz_plugin/BoundingBoxArray + Enabled: true + Name: BBox + Queue Size: 10 + Topic: /robot/cpp/centerpp_node/box + Unreliable: false + Value: true + alpha: 0.800000011920929 + color: 25; 255; 0 + coloring: Label + line width: 0.20000000298023224 + only edge: true + show coords: false + - Class: jsk_rviz_plugin/BoundingBoxArray + Enabled: true + Name: Dynamic_BBox + Queue Size: 10 + Topic: /robot/cpp/centerpp_node/dynamic_box + Unreliable: false + Value: true + alpha: 0.800000011920929 + color: 25; 255; 0 + coloring: Flat color + line width: 0.20000000298023224 + only edge: false + show coords: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: Point_Cluster + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.30000001192092896 + Style: Spheres + Topic: /robot/cpp/centerpp_node/pointcloud_cluster + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /robot/cpp/centerpp_node/centerpoint_vel + Name: CenterPoint_vel + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/Marker + Enabled: false + Marker Topic: /robot/cpp/centerpp_node/object_vel_arrows + Name: Tracking_Arrows + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/Marker + Enabled: false + Marker Topic: /robot/cpp/centerpp_node/tracking_center + Name: Tracking_Center + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/Marker + Enabled: false + Marker Topic: /robot/cpp/centerpp_node/box_markers + Name: BoundingBox_Markers + Namespaces: + {} + Queue Size: 100 + Value: false + - Class: rviz/Marker + Enabled: true + Marker Topic: /robot/trlo/odom_node/robot + Name: Robot + Namespaces: + robot: true + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /robot/cpp/centerpp_node/center_markers + Name: Dynamic_Objects + Namespaces: + center_points: true + Queue Size: 100 + Value: true + Enabled: true + Global Options: + Background Color: 0; 0; 0 + Default Light: true + Fixed Frame: robot/odom + Frame Rate: 60 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/ThirdPersonFollower + Distance: 49.367942810058594 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: -15.700443267822266 + Y: 2.9954674243927 + Z: 1.4299042959464714e-05 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.44849276542663574 + Target Frame: robot/base_link + Yaw: 3.139038562774658 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1043 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 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 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1848 + X: 712 + Y: 27 diff --git a/trlo/model/center_pointpillars/centerpoint.scn.onnx b/trlo/model/center_pointpillars/centerpoint.scn.onnx new file mode 100644 index 0000000..bc7904a Binary files /dev/null and b/trlo/model/center_pointpillars/centerpoint.scn.onnx differ diff --git a/trlo/model/center_pointpillars/rpn_centerhead_sim.8513.log b/trlo/model/center_pointpillars/rpn_centerhead_sim.8513.log new file mode 100644 index 0000000..12b0630 --- /dev/null +++ b/trlo/model/center_pointpillars/rpn_centerhead_sim.8513.log @@ -0,0 +1,20176 @@ +&&&& RUNNING TensorRT.trtexec [TensorRT v8503] # trtexec --onnx=model/rpn_centerhead_sim.onnx --saveEngine=model/rpn_centerhead_sim.plan.8513 --workspace=4096 --fp16 --outputIOFormats=fp16:chw --inputIOFormats=fp16:chw --verbose --dumpLayerInfo --dumpProfile --separateProfileRun --profilingVerbosity=detailed +[03/18/2024-15:12:39] [W] --workspace flag has been deprecated by --memPoolSize flag. +[03/18/2024-15:12:39] [I] === Model Options === +[03/18/2024-15:12:39] [I] Format: ONNX +[03/18/2024-15:12:39] [I] Model: model/rpn_centerhead_sim.onnx +[03/18/2024-15:12:39] [I] Output: +[03/18/2024-15:12:39] [I] === Build Options === +[03/18/2024-15:12:39] [I] Max batch: explicit batch +[03/18/2024-15:12:39] [I] Memory Pools: workspace: 4096 MiB, dlaSRAM: default, dlaLocalDRAM: default, dlaGlobalDRAM: default +[03/18/2024-15:12:39] [I] minTiming: 1 +[03/18/2024-15:12:39] [I] avgTiming: 8 +[03/18/2024-15:12:39] [I] Precision: FP32+FP16 +[03/18/2024-15:12:39] [I] LayerPrecisions: +[03/18/2024-15:12:39] [I] Calibration: +[03/18/2024-15:12:39] [I] Refit: Disabled +[03/18/2024-15:12:39] [I] Sparsity: Disabled +[03/18/2024-15:12:39] [I] Safe mode: Disabled +[03/18/2024-15:12:39] [I] DirectIO mode: Disabled +[03/18/2024-15:12:39] [I] Restricted mode: Disabled +[03/18/2024-15:12:39] [I] Build only: Disabled +[03/18/2024-15:12:39] [I] Save engine: model/rpn_centerhead_sim.plan.8513 +[03/18/2024-15:12:39] [I] Load engine: +[03/18/2024-15:12:39] [I] Profiling verbosity: 2 +[03/18/2024-15:12:39] [I] Tactic sources: Using default tactic sources +[03/18/2024-15:12:39] [I] timingCacheMode: local +[03/18/2024-15:12:39] [I] timingCacheFile: +[03/18/2024-15:12:39] [I] Heuristic: Disabled +[03/18/2024-15:12:39] [I] Preview Features: Use default preview flags. +[03/18/2024-15:12:39] [I] Input(s): fp16:chw +[03/18/2024-15:12:39] [I] Output(s): fp16:chw +[03/18/2024-15:12:39] [I] Input build shapes: model +[03/18/2024-15:12:39] [I] Input calibration shapes: model +[03/18/2024-15:12:39] [I] === System Options === +[03/18/2024-15:12:39] [I] Device: 0 +[03/18/2024-15:12:39] [I] DLACore: +[03/18/2024-15:12:39] [I] Plugins: +[03/18/2024-15:12:39] [I] === Inference Options === +[03/18/2024-15:12:39] [I] Batch: Explicit +[03/18/2024-15:12:39] [I] Input inference shapes: model +[03/18/2024-15:12:39] [I] Iterations: 10 +[03/18/2024-15:12:39] [I] Duration: 3s (+ 200ms warm up) +[03/18/2024-15:12:39] [I] Sleep time: 0ms +[03/18/2024-15:12:39] [I] Idle time: 0ms +[03/18/2024-15:12:39] [I] Streams: 1 +[03/18/2024-15:12:39] [I] ExposeDMA: Disabled +[03/18/2024-15:12:39] [I] Data transfers: Enabled +[03/18/2024-15:12:39] [I] Spin-wait: Disabled +[03/18/2024-15:12:39] [I] Multithreading: Disabled +[03/18/2024-15:12:39] [I] CUDA Graph: Disabled +[03/18/2024-15:12:39] [I] Separate profiling: Enabled +[03/18/2024-15:12:39] [I] Time Deserialize: Disabled +[03/18/2024-15:12:39] [I] Time Refit: Disabled +[03/18/2024-15:12:39] [I] NVTX verbosity: 2 +[03/18/2024-15:12:39] [I] Persistent Cache Ratio: 0 +[03/18/2024-15:12:39] [I] Inputs: +[03/18/2024-15:12:39] [I] === Reporting Options === +[03/18/2024-15:12:39] [I] Verbose: Enabled +[03/18/2024-15:12:39] [I] Averages: 10 inferences +[03/18/2024-15:12:39] [I] Percentiles: 90,95,99 +[03/18/2024-15:12:39] [I] Dump refittable layers:Disabled +[03/18/2024-15:12:39] [I] Dump output: Disabled +[03/18/2024-15:12:39] [I] Profile: Enabled +[03/18/2024-15:12:39] [I] Export timing to JSON file: +[03/18/2024-15:12:39] [I] Export output to JSON file: +[03/18/2024-15:12:39] [I] Export profile to JSON file: +[03/18/2024-15:12:39] [I] +[03/18/2024-15:12:39] [I] === Device Information === +[03/18/2024-15:12:39] [I] Selected Device: NVIDIA GeForce RTX 3060 Laptop GPU +[03/18/2024-15:12:39] [I] Compute Capability: 8.6 +[03/18/2024-15:12:39] [I] SMs: 30 +[03/18/2024-15:12:39] [I] Compute Clock Rate: 1.425 GHz +[03/18/2024-15:12:39] [I] Device Global Memory: 5913 MiB +[03/18/2024-15:12:39] [I] Shared Memory per SM: 100 KiB +[03/18/2024-15:12:39] [I] Memory Bus Width: 192 bits (ECC disabled) +[03/18/2024-15:12:39] [I] Memory Clock Rate: 7.001 GHz +[03/18/2024-15:12:39] [I] +[03/18/2024-15:12:39] [I] TensorRT version: 8.5.3 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::BatchedNMSDynamic_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::BatchedNMS_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::BatchTilePlugin_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::Clip_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::CoordConvAC version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::CropAndResizeDynamic version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::CropAndResize version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::DecodeBbox3DPlugin version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::DetectionLayer_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::EfficientNMS_Explicit_TF_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::EfficientNMS_Implicit_TF_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::EfficientNMS_ONNX_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::EfficientNMS_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::FlattenConcat_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::fMHA_V2 version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::fMHCA version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::GenerateDetection_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::GridAnchor_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::GridAnchorRect_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::GroupNorm version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::InstanceNormalization_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::InstanceNormalization_TRT version 2 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::LayerNorm version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::LReLU_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::MultilevelCropAndResize_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::MultilevelProposeROI_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::MultiscaleDeformableAttnPlugin_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::NMSDynamic_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::NMS_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::Normalize_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::PillarScatterPlugin version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::PriorBox_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::ProposalDynamic version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::ProposalLayer_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::Proposal version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::PyramidROIAlign_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::Region_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::Reorg_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::ResizeNearest_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::ROIAlign_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::RPROI_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::ScatterND version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::SeqLen2Spatial version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::SpecialSlice_TRT version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::SplitGeLU version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::Split version 1 +[03/18/2024-15:12:39] [V] [TRT] Registered plugin creator - ::VoxelGeneratorPlugin version 1 +[03/18/2024-15:12:39] [I] [TRT] [MemUsageChange] Init CUDA: CPU +14, GPU +0, now: CPU 25, GPU 694 (MiB) +[03/18/2024-15:12:39] [V] [TRT] Trying to load shared library libnvinfer_builder_resource.so.8.5.3 +[03/18/2024-15:12:39] [V] [TRT] Loaded shared library libnvinfer_builder_resource.so.8.5.3 +[03/18/2024-15:12:40] [I] [TRT] [MemUsageChange] Init builder kernel library: CPU +546, GPU +118, now: CPU 626, GPU 812 (MiB) +[03/18/2024-15:12:40] [V] [TRT] CUDA lazy loading is enabled. +[03/18/2024-15:12:40] [I] Start parsing network model +[03/18/2024-15:12:40] [I] [TRT] ---------------------------------------------------------------- +[03/18/2024-15:12:40] [I] [TRT] Input filename: model/rpn_centerhead_sim.onnx +[03/18/2024-15:12:40] [I] [TRT] ONNX IR version: 0.0.6 +[03/18/2024-15:12:40] [I] [TRT] Opset version: 11 +[03/18/2024-15:12:40] [I] [TRT] Producer name: pytorch +[03/18/2024-15:12:40] [I] [TRT] Producer version: 1.11.0 +[03/18/2024-15:12:40] [I] [TRT] Domain: +[03/18/2024-15:12:40] [I] [TRT] Model version: 0 +[03/18/2024-15:12:40] [I] [TRT] Doc string: +[03/18/2024-15:12:40] [I] [TRT] ---------------------------------------------------------------- +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::BatchedNMSDynamic_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::BatchedNMS_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::BatchTilePlugin_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::Clip_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::CoordConvAC version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::CropAndResizeDynamic version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::CropAndResize version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::DecodeBbox3DPlugin version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::DetectionLayer_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::EfficientNMS_Explicit_TF_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::EfficientNMS_Implicit_TF_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::EfficientNMS_ONNX_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::EfficientNMS_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::FlattenConcat_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::fMHA_V2 version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::fMHCA version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::GenerateDetection_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::GridAnchor_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::GridAnchorRect_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::GroupNorm version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::InstanceNormalization_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::InstanceNormalization_TRT version 2 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::LayerNorm version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::LReLU_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::MultilevelCropAndResize_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::MultilevelProposeROI_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::MultiscaleDeformableAttnPlugin_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::NMSDynamic_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::NMS_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::Normalize_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::PillarScatterPlugin version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::PriorBox_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::ProposalDynamic version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::ProposalLayer_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::Proposal version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::PyramidROIAlign_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::Region_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::Reorg_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::ResizeNearest_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::ROIAlign_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::RPROI_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::ScatterND version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::SeqLen2Spatial version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::SpecialSlice_TRT version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::SplitGeLU version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::Split version 1 +[03/18/2024-15:12:40] [V] [TRT] Plugin creator already registered - ::VoxelGeneratorPlugin version 1 +[03/18/2024-15:12:40] [V] [TRT] Adding network input: input with dtype: float32, dimensions: (1, 256, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input for ONNX tensor: input +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.neck.deblocks.1.0.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.neck.deblocks.1.1.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.neck.deblocks.1.1.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.neck.deblocks.1.1.running_mean +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.neck.deblocks.1.1.running_var +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.0.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.1.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.2.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.3.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.4.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: model.bbox_head.tasks.5.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_797 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_798 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_800 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_801 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_803 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_804 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_806 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_807 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_809 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_810 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_812 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_813 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_815 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_816 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_818 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_819 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_821 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_822 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_824 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_825 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_827 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_828 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_830 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_831 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_833 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_834 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_836 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_837 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_839 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_840 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_842 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_843 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_845 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_846 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_848 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_849 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_851 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_852 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_854 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_855 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_857 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_858 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_860 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_861 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_863 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_864 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_866 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_867 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_869 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_870 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_872 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_873 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_875 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_876 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_878 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_879 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_881 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_882 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_884 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_885 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_887 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_888 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_890 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_891 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_893 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_894 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_896 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_897 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_899 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_900 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_902 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_903 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_905 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_906 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_908 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_909 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_911 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_912 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_914 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_915 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_917 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_918 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_920 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_921 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_923 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_924 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_926 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_927 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_929 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_930 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_932 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_933 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_935 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_936 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_938 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_939 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_941 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_942 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_944 +[03/18/2024-15:12:40] [V] [TRT] Importing initializer: onnx::Conv_945 +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_15 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_797 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_798 +[03/18/2024-15:12:40] [V] [TRT] Conv_15 [Conv] inputs: [input -> (1, 256, 180, 180)[FLOAT]], [onnx::Conv_797 -> (128, 256, 3, 3)[FLOAT]], [onnx::Conv_798 -> (128)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 256, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_15 for ONNX node: Conv_15 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 128 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.8 for ONNX tensor: input.8 +[03/18/2024-15:12:40] [V] [TRT] Conv_15 [Conv] outputs: [input.8 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_16 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.8 +[03/18/2024-15:12:40] [V] [TRT] Relu_16 [Relu] inputs: [input.8 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_16 for ONNX node: Relu_16 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.12 for ONNX tensor: input.12 +[03/18/2024-15:12:40] [V] [TRT] Relu_16 [Relu] outputs: [input.12 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_17 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.12 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_800 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_801 +[03/18/2024-15:12:40] [V] [TRT] Conv_17 [Conv] inputs: [input.12 -> (1, 128, 180, 180)[FLOAT]], [onnx::Conv_800 -> (128, 128, 3, 3)[FLOAT]], [onnx::Conv_801 -> (128)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_17 for ONNX node: Conv_17 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 128 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.20 for ONNX tensor: input.20 +[03/18/2024-15:12:40] [V] [TRT] Conv_17 [Conv] outputs: [input.20 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_18 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.20 +[03/18/2024-15:12:40] [V] [TRT] Relu_18 [Relu] inputs: [input.20 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_18 for ONNX node: Relu_18 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.24 for ONNX tensor: input.24 +[03/18/2024-15:12:40] [V] [TRT] Relu_18 [Relu] outputs: [input.24 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_19 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.24 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_803 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_804 +[03/18/2024-15:12:40] [V] [TRT] Conv_19 [Conv] inputs: [input.24 -> (1, 128, 180, 180)[FLOAT]], [onnx::Conv_803 -> (128, 128, 3, 3)[FLOAT]], [onnx::Conv_804 -> (128)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_19 for ONNX node: Conv_19 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 128 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.32 for ONNX tensor: input.32 +[03/18/2024-15:12:40] [V] [TRT] Conv_19 [Conv] outputs: [input.32 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_20 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.32 +[03/18/2024-15:12:40] [V] [TRT] Relu_20 [Relu] inputs: [input.32 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_20 for ONNX node: Relu_20 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.36 for ONNX tensor: input.36 +[03/18/2024-15:12:40] [V] [TRT] Relu_20 [Relu] outputs: [input.36 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_21 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.36 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_806 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_807 +[03/18/2024-15:12:40] [V] [TRT] Conv_21 [Conv] inputs: [input.36 -> (1, 128, 180, 180)[FLOAT]], [onnx::Conv_806 -> (128, 128, 3, 3)[FLOAT]], [onnx::Conv_807 -> (128)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_21 for ONNX node: Conv_21 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 128 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.44 for ONNX tensor: input.44 +[03/18/2024-15:12:40] [V] [TRT] Conv_21 [Conv] outputs: [input.44 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_22 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.44 +[03/18/2024-15:12:40] [V] [TRT] Relu_22 [Relu] inputs: [input.44 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_22 for ONNX node: Relu_22 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.48 for ONNX tensor: input.48 +[03/18/2024-15:12:40] [V] [TRT] Relu_22 [Relu] outputs: [input.48 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_23 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.48 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_809 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_810 +[03/18/2024-15:12:40] [V] [TRT] Conv_23 [Conv] inputs: [input.48 -> (1, 128, 180, 180)[FLOAT]], [onnx::Conv_809 -> (128, 128, 3, 3)[FLOAT]], [onnx::Conv_810 -> (128)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_23 for ONNX node: Conv_23 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 128 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.56 for ONNX tensor: input.56 +[03/18/2024-15:12:40] [V] [TRT] Conv_23 [Conv] outputs: [input.56 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_24 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.56 +[03/18/2024-15:12:40] [V] [TRT] Relu_24 [Relu] inputs: [input.56 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_24 for ONNX node: Relu_24 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.60 for ONNX tensor: input.60 +[03/18/2024-15:12:40] [V] [TRT] Relu_24 [Relu] outputs: [input.60 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_25 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.60 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_812 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_813 +[03/18/2024-15:12:40] [V] [TRT] Conv_25 [Conv] inputs: [input.60 -> (1, 128, 180, 180)[FLOAT]], [onnx::Conv_812 -> (128, 128, 3, 3)[FLOAT]], [onnx::Conv_813 -> (128)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_25 for ONNX node: Conv_25 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 128 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.68 for ONNX tensor: input.68 +[03/18/2024-15:12:40] [V] [TRT] Conv_25 [Conv] outputs: [input.68 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_26 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.68 +[03/18/2024-15:12:40] [V] [TRT] Relu_26 [Relu] inputs: [input.68 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_26 for ONNX node: Relu_26 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.72 for ONNX tensor: input.72 +[03/18/2024-15:12:40] [V] [TRT] Relu_26 [Relu] outputs: [input.72 -> (1, 128, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_27 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.72 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_815 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_816 +[03/18/2024-15:12:40] [V] [TRT] Conv_27 [Conv] inputs: [input.72 -> (1, 128, 180, 180)[FLOAT]], [onnx::Conv_815 -> (256, 128, 1, 1)[FLOAT]], [onnx::Conv_816 -> (256)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_27 for ONNX node: Conv_27 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (1, 1), strides: (1, 1), prepadding: (0, 0), postpadding: (0, 0), dilations: (1, 1), numOutputs: 256 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 256, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.80 for ONNX tensor: input.80 +[03/18/2024-15:12:40] [V] [TRT] Conv_27 [Conv] outputs: [input.80 -> (1, 256, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_28 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.80 +[03/18/2024-15:12:40] [V] [TRT] Relu_28 [Relu] inputs: [input.80 -> (1, 256, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_28 for ONNX node: Relu_28 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: onnx::Concat_602 for ONNX tensor: onnx::Concat_602 +[03/18/2024-15:12:40] [V] [TRT] Relu_28 [Relu] outputs: [onnx::Concat_602 -> (1, 256, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_44 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.72 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_818 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_819 +[03/18/2024-15:12:40] [V] [TRT] Conv_44 [Conv] inputs: [input.72 -> (1, 128, 180, 180)[FLOAT]], [onnx::Conv_818 -> (256, 128, 3, 3)[FLOAT]], [onnx::Conv_819 -> (256)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 128, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_44 for ONNX node: Conv_44 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (2, 2), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 256 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.92 for ONNX tensor: input.92 +[03/18/2024-15:12:40] [V] [TRT] Conv_44 [Conv] outputs: [input.92 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_45 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.92 +[03/18/2024-15:12:40] [V] [TRT] Relu_45 [Relu] inputs: [input.92 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_45 for ONNX node: Relu_45 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.96 for ONNX tensor: input.96 +[03/18/2024-15:12:40] [V] [TRT] Relu_45 [Relu] outputs: [input.96 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_46 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.96 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_821 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_822 +[03/18/2024-15:12:40] [V] [TRT] Conv_46 [Conv] inputs: [input.96 -> (1, 256, 90, 90)[FLOAT]], [onnx::Conv_821 -> (256, 256, 3, 3)[FLOAT]], [onnx::Conv_822 -> (256)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_46 for ONNX node: Conv_46 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 256 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.104 for ONNX tensor: input.104 +[03/18/2024-15:12:40] [V] [TRT] Conv_46 [Conv] outputs: [input.104 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_47 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.104 +[03/18/2024-15:12:40] [V] [TRT] Relu_47 [Relu] inputs: [input.104 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_47 for ONNX node: Relu_47 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.108 for ONNX tensor: input.108 +[03/18/2024-15:12:40] [V] [TRT] Relu_47 [Relu] outputs: [input.108 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_48 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.108 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_824 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_825 +[03/18/2024-15:12:40] [V] [TRT] Conv_48 [Conv] inputs: [input.108 -> (1, 256, 90, 90)[FLOAT]], [onnx::Conv_824 -> (256, 256, 3, 3)[FLOAT]], [onnx::Conv_825 -> (256)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_48 for ONNX node: Conv_48 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 256 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.116 for ONNX tensor: input.116 +[03/18/2024-15:12:40] [V] [TRT] Conv_48 [Conv] outputs: [input.116 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_49 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.116 +[03/18/2024-15:12:40] [V] [TRT] Relu_49 [Relu] inputs: [input.116 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_49 for ONNX node: Relu_49 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.120 for ONNX tensor: input.120 +[03/18/2024-15:12:40] [V] [TRT] Relu_49 [Relu] outputs: [input.120 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_50 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.120 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_827 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_828 +[03/18/2024-15:12:40] [V] [TRT] Conv_50 [Conv] inputs: [input.120 -> (1, 256, 90, 90)[FLOAT]], [onnx::Conv_827 -> (256, 256, 3, 3)[FLOAT]], [onnx::Conv_828 -> (256)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_50 for ONNX node: Conv_50 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 256 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.128 for ONNX tensor: input.128 +[03/18/2024-15:12:40] [V] [TRT] Conv_50 [Conv] outputs: [input.128 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_51 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.128 +[03/18/2024-15:12:40] [V] [TRT] Relu_51 [Relu] inputs: [input.128 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_51 for ONNX node: Relu_51 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.132 for ONNX tensor: input.132 +[03/18/2024-15:12:40] [V] [TRT] Relu_51 [Relu] outputs: [input.132 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_52 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.132 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_830 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_831 +[03/18/2024-15:12:40] [V] [TRT] Conv_52 [Conv] inputs: [input.132 -> (1, 256, 90, 90)[FLOAT]], [onnx::Conv_830 -> (256, 256, 3, 3)[FLOAT]], [onnx::Conv_831 -> (256)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_52 for ONNX node: Conv_52 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 256 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.140 for ONNX tensor: input.140 +[03/18/2024-15:12:40] [V] [TRT] Conv_52 [Conv] outputs: [input.140 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_53 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.140 +[03/18/2024-15:12:40] [V] [TRT] Relu_53 [Relu] inputs: [input.140 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_53 for ONNX node: Relu_53 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.144 for ONNX tensor: input.144 +[03/18/2024-15:12:40] [V] [TRT] Relu_53 [Relu] outputs: [input.144 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_54 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.144 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_833 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_834 +[03/18/2024-15:12:40] [V] [TRT] Conv_54 [Conv] inputs: [input.144 -> (1, 256, 90, 90)[FLOAT]], [onnx::Conv_833 -> (256, 256, 3, 3)[FLOAT]], [onnx::Conv_834 -> (256)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_54 for ONNX node: Conv_54 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 256 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 256, 90, 90) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.152 for ONNX tensor: input.152 +[03/18/2024-15:12:40] [V] [TRT] Conv_54 [Conv] outputs: [input.152 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_55 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.152 +[03/18/2024-15:12:40] [V] [TRT] Relu_55 [Relu] inputs: [input.152 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_55 for ONNX node: Relu_55 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: onnx::ConvTranspose_644 for ONNX tensor: onnx::ConvTranspose_644 +[03/18/2024-15:12:40] [V] [TRT] Relu_55 [Relu] outputs: [onnx::ConvTranspose_644 -> (1, 256, 90, 90)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: ConvTranspose_56 [ConvTranspose] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::ConvTranspose_644 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.neck.deblocks.1.0.weight +[03/18/2024-15:12:40] [V] [TRT] ConvTranspose_56 [ConvTranspose] inputs: [onnx::ConvTranspose_644 -> (1, 256, 90, 90)[FLOAT]], [model.neck.deblocks.1.0.weight -> (256, 256, 2, 2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Running deconvolution with: +Padding mode: NOTSET +Pre-padding: (0, 0) +Post-padding: (0, 0) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: ConvTranspose_56 for ONNX node: ConvTranspose_56 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.156 for ONNX tensor: input.156 +[03/18/2024-15:12:40] [V] [TRT] ConvTranspose_56 [ConvTranspose] outputs: [input.156 -> (1, 256, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: BatchNormalization_57 [BatchNormalization] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.156 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.neck.deblocks.1.1.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.neck.deblocks.1.1.bias +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.neck.deblocks.1.1.running_mean +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.neck.deblocks.1.1.running_var +[03/18/2024-15:12:40] [V] [TRT] BatchNormalization_57 [BatchNormalization] inputs: [input.156 -> (1, 256, 180, 180)[FLOAT]], [model.neck.deblocks.1.1.weight -> (256)[FLOAT]], [model.neck.deblocks.1.1.bias -> (256)[FLOAT]], [model.neck.deblocks.1.1.running_mean -> (256)[FLOAT]], [model.neck.deblocks.1.1.running_var -> (256)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: BatchNormalization_57 for ONNX node: BatchNormalization_57 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.160 for ONNX tensor: input.160 +[03/18/2024-15:12:40] [V] [TRT] BatchNormalization_57 [BatchNormalization] outputs: [input.160 -> (1, 256, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_58 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.160 +[03/18/2024-15:12:40] [V] [TRT] Relu_58 [Relu] inputs: [input.160 -> (1, 256, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_58 for ONNX node: Relu_58 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: onnx::Concat_647 for ONNX tensor: onnx::Concat_647 +[03/18/2024-15:12:40] [V] [TRT] Relu_58 [Relu] outputs: [onnx::Concat_647 -> (1, 256, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Concat_59 [Concat] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Concat_602 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Concat_647 +[03/18/2024-15:12:40] [V] [TRT] Concat_59 [Concat] inputs: [onnx::Concat_602 -> (1, 256, 180, 180)[FLOAT]], [onnx::Concat_647 -> (1, 256, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Concat_59 for ONNX node: Concat_59 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.164 for ONNX tensor: input.164 +[03/18/2024-15:12:40] [V] [TRT] Concat_59 [Concat] outputs: [input.164 -> (1, 512, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_60 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.164 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_836 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_837 +[03/18/2024-15:12:40] [V] [TRT] Conv_60 [Conv] inputs: [input.164 -> (1, 512, 180, 180)[FLOAT]], [onnx::Conv_836 -> (64, 512, 3, 3)[FLOAT]], [onnx::Conv_837 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 512, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_60 for ONNX node: Conv_60 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.172 for ONNX tensor: input.172 +[03/18/2024-15:12:40] [V] [TRT] Conv_60 [Conv] outputs: [input.172 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_61 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.172 +[03/18/2024-15:12:40] [V] [TRT] Relu_61 [Relu] inputs: [input.172 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_61 for ONNX node: Relu_61 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: onnx::Conv_651 for ONNX tensor: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Relu_61 [Relu] outputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_62 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_839 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_840 +[03/18/2024-15:12:40] [V] [TRT] Conv_62 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_839 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_840 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_62 for ONNX node: Conv_62 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.180 for ONNX tensor: input.180 +[03/18/2024-15:12:40] [V] [TRT] Conv_62 [Conv] outputs: [input.180 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_63 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.180 +[03/18/2024-15:12:40] [V] [TRT] Relu_63 [Relu] inputs: [input.180 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_63 for ONNX node: Relu_63 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.184 for ONNX tensor: input.184 +[03/18/2024-15:12:40] [V] [TRT] Relu_63 [Relu] outputs: [input.184 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_64 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.184 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_64 [Conv] inputs: [input.184 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.0.reg.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.0.reg.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_64 for ONNX node: Conv_64 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: reg_0_1 for ONNX tensor: reg_0 +[03/18/2024-15:12:40] [V] [TRT] Conv_64 [Conv] outputs: [reg_0 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_65 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_842 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_843 +[03/18/2024-15:12:40] [V] [TRT] Conv_65 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_842 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_843 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_65 for ONNX node: Conv_65 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.192 for ONNX tensor: input.192 +[03/18/2024-15:12:40] [V] [TRT] Conv_65 [Conv] outputs: [input.192 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_66 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.192 +[03/18/2024-15:12:40] [V] [TRT] Relu_66 [Relu] inputs: [input.192 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_66 for ONNX node: Relu_66 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.196 for ONNX tensor: input.196 +[03/18/2024-15:12:40] [V] [TRT] Relu_66 [Relu] outputs: [input.196 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_67 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.196 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_67 [Conv] inputs: [input.196 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.0.height.3.weight -> (1, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.0.height.3.bias -> (1)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_67 for ONNX node: Conv_67 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 1 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 1, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: height_0_2 for ONNX tensor: height_0 +[03/18/2024-15:12:40] [V] [TRT] Conv_67 [Conv] outputs: [height_0 -> (1, 1, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_68 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_845 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_846 +[03/18/2024-15:12:40] [V] [TRT] Conv_68 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_845 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_846 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_68 for ONNX node: Conv_68 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.204 for ONNX tensor: input.204 +[03/18/2024-15:12:40] [V] [TRT] Conv_68 [Conv] outputs: [input.204 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_69 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.204 +[03/18/2024-15:12:40] [V] [TRT] Relu_69 [Relu] inputs: [input.204 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_69 for ONNX node: Relu_69 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.208 for ONNX tensor: input.208 +[03/18/2024-15:12:40] [V] [TRT] Relu_69 [Relu] outputs: [input.208 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_70 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.208 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_70 [Conv] inputs: [input.208 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.0.dim.3.weight -> (3, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.0.dim.3.bias -> (3)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_70 for ONNX node: Conv_70 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 3 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 3, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: dim_0_3 for ONNX tensor: dim_0 +[03/18/2024-15:12:40] [V] [TRT] Conv_70 [Conv] outputs: [dim_0 -> (1, 3, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_71 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_848 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_849 +[03/18/2024-15:12:40] [V] [TRT] Conv_71 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_848 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_849 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_71 for ONNX node: Conv_71 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.216 for ONNX tensor: input.216 +[03/18/2024-15:12:40] [V] [TRT] Conv_71 [Conv] outputs: [input.216 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_72 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.216 +[03/18/2024-15:12:40] [V] [TRT] Relu_72 [Relu] inputs: [input.216 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_72 for ONNX node: Relu_72 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.220 for ONNX tensor: input.220 +[03/18/2024-15:12:40] [V] [TRT] Relu_72 [Relu] outputs: [input.220 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_73 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.220 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_73 [Conv] inputs: [input.220 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.0.rot.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.0.rot.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_73 for ONNX node: Conv_73 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: rot_0_4 for ONNX tensor: rot_0 +[03/18/2024-15:12:40] [V] [TRT] Conv_73 [Conv] outputs: [rot_0 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_74 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_851 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_852 +[03/18/2024-15:12:40] [V] [TRT] Conv_74 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_851 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_852 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_74 for ONNX node: Conv_74 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.228 for ONNX tensor: input.228 +[03/18/2024-15:12:40] [V] [TRT] Conv_74 [Conv] outputs: [input.228 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_75 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.228 +[03/18/2024-15:12:40] [V] [TRT] Relu_75 [Relu] inputs: [input.228 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_75 for ONNX node: Relu_75 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.232 for ONNX tensor: input.232 +[03/18/2024-15:12:40] [V] [TRT] Relu_75 [Relu] outputs: [input.232 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_76 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.232 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_76 [Conv] inputs: [input.232 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.0.vel.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.0.vel.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_76 for ONNX node: Conv_76 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: vel_0_5 for ONNX tensor: vel_0 +[03/18/2024-15:12:40] [V] [TRT] Conv_76 [Conv] outputs: [vel_0 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_77 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_854 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_855 +[03/18/2024-15:12:40] [V] [TRT] Conv_77 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_854 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_855 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_77 for ONNX node: Conv_77 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.240 for ONNX tensor: input.240 +[03/18/2024-15:12:40] [V] [TRT] Conv_77 [Conv] outputs: [input.240 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_78 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.240 +[03/18/2024-15:12:40] [V] [TRT] Relu_78 [Relu] inputs: [input.240 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_78 for ONNX node: Relu_78 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.244 for ONNX tensor: input.244 +[03/18/2024-15:12:40] [V] [TRT] Relu_78 [Relu] outputs: [input.244 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_79 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.244 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.0.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_79 [Conv] inputs: [input.244 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.0.hm.3.weight -> (1, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.0.hm.3.bias -> (1)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_79 for ONNX node: Conv_79 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 1 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 1, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: hm_0_6 for ONNX tensor: hm_0 +[03/18/2024-15:12:40] [V] [TRT] Conv_79 [Conv] outputs: [hm_0 -> (1, 1, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_80 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_857 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_858 +[03/18/2024-15:12:40] [V] [TRT] Conv_80 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_857 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_858 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_80 for ONNX node: Conv_80 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.252 for ONNX tensor: input.252 +[03/18/2024-15:12:40] [V] [TRT] Conv_80 [Conv] outputs: [input.252 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_81 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.252 +[03/18/2024-15:12:40] [V] [TRT] Relu_81 [Relu] inputs: [input.252 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_81 for ONNX node: Relu_81 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.256 for ONNX tensor: input.256 +[03/18/2024-15:12:40] [V] [TRT] Relu_81 [Relu] outputs: [input.256 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_82 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.256 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_82 [Conv] inputs: [input.256 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.1.reg.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.1.reg.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_82 for ONNX node: Conv_82 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: reg_1_7 for ONNX tensor: reg_1 +[03/18/2024-15:12:40] [V] [TRT] Conv_82 [Conv] outputs: [reg_1 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_83 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_860 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_861 +[03/18/2024-15:12:40] [V] [TRT] Conv_83 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_860 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_861 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_83 for ONNX node: Conv_83 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.264 for ONNX tensor: input.264 +[03/18/2024-15:12:40] [V] [TRT] Conv_83 [Conv] outputs: [input.264 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_84 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.264 +[03/18/2024-15:12:40] [V] [TRT] Relu_84 [Relu] inputs: [input.264 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_84 for ONNX node: Relu_84 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.268 for ONNX tensor: input.268 +[03/18/2024-15:12:40] [V] [TRT] Relu_84 [Relu] outputs: [input.268 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_85 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.268 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_85 [Conv] inputs: [input.268 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.1.height.3.weight -> (1, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.1.height.3.bias -> (1)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_85 for ONNX node: Conv_85 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 1 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 1, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: height_1_8 for ONNX tensor: height_1 +[03/18/2024-15:12:40] [V] [TRT] Conv_85 [Conv] outputs: [height_1 -> (1, 1, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_86 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_863 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_864 +[03/18/2024-15:12:40] [V] [TRT] Conv_86 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_863 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_864 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_86 for ONNX node: Conv_86 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.276 for ONNX tensor: input.276 +[03/18/2024-15:12:40] [V] [TRT] Conv_86 [Conv] outputs: [input.276 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_87 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.276 +[03/18/2024-15:12:40] [V] [TRT] Relu_87 [Relu] inputs: [input.276 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_87 for ONNX node: Relu_87 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.280 for ONNX tensor: input.280 +[03/18/2024-15:12:40] [V] [TRT] Relu_87 [Relu] outputs: [input.280 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_88 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.280 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_88 [Conv] inputs: [input.280 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.1.dim.3.weight -> (3, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.1.dim.3.bias -> (3)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_88 for ONNX node: Conv_88 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 3 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 3, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: dim_1_9 for ONNX tensor: dim_1 +[03/18/2024-15:12:40] [V] [TRT] Conv_88 [Conv] outputs: [dim_1 -> (1, 3, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_89 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_866 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_867 +[03/18/2024-15:12:40] [V] [TRT] Conv_89 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_866 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_867 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_89 for ONNX node: Conv_89 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.288 for ONNX tensor: input.288 +[03/18/2024-15:12:40] [V] [TRT] Conv_89 [Conv] outputs: [input.288 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_90 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.288 +[03/18/2024-15:12:40] [V] [TRT] Relu_90 [Relu] inputs: [input.288 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_90 for ONNX node: Relu_90 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.292 for ONNX tensor: input.292 +[03/18/2024-15:12:40] [V] [TRT] Relu_90 [Relu] outputs: [input.292 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_91 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.292 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_91 [Conv] inputs: [input.292 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.1.rot.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.1.rot.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_91 for ONNX node: Conv_91 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: rot_1_10 for ONNX tensor: rot_1 +[03/18/2024-15:12:40] [V] [TRT] Conv_91 [Conv] outputs: [rot_1 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_92 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_869 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_870 +[03/18/2024-15:12:40] [V] [TRT] Conv_92 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_869 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_870 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_92 for ONNX node: Conv_92 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.300 for ONNX tensor: input.300 +[03/18/2024-15:12:40] [V] [TRT] Conv_92 [Conv] outputs: [input.300 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_93 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.300 +[03/18/2024-15:12:40] [V] [TRT] Relu_93 [Relu] inputs: [input.300 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_93 for ONNX node: Relu_93 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.304 for ONNX tensor: input.304 +[03/18/2024-15:12:40] [V] [TRT] Relu_93 [Relu] outputs: [input.304 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_94 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.304 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_94 [Conv] inputs: [input.304 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.1.vel.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.1.vel.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_94 for ONNX node: Conv_94 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: vel_1_11 for ONNX tensor: vel_1 +[03/18/2024-15:12:40] [V] [TRT] Conv_94 [Conv] outputs: [vel_1 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_95 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_872 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_873 +[03/18/2024-15:12:40] [V] [TRT] Conv_95 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_872 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_873 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_95 for ONNX node: Conv_95 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.312 for ONNX tensor: input.312 +[03/18/2024-15:12:40] [V] [TRT] Conv_95 [Conv] outputs: [input.312 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_96 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.312 +[03/18/2024-15:12:40] [V] [TRT] Relu_96 [Relu] inputs: [input.312 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_96 for ONNX node: Relu_96 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.316 for ONNX tensor: input.316 +[03/18/2024-15:12:40] [V] [TRT] Relu_96 [Relu] outputs: [input.316 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_97 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.316 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.1.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_97 [Conv] inputs: [input.316 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.1.hm.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.1.hm.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_97 for ONNX node: Conv_97 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: hm_1_12 for ONNX tensor: hm_1 +[03/18/2024-15:12:40] [V] [TRT] Conv_97 [Conv] outputs: [hm_1 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_98 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_875 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_876 +[03/18/2024-15:12:40] [V] [TRT] Conv_98 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_875 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_876 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_98 for ONNX node: Conv_98 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.324 for ONNX tensor: input.324 +[03/18/2024-15:12:40] [V] [TRT] Conv_98 [Conv] outputs: [input.324 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_99 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.324 +[03/18/2024-15:12:40] [V] [TRT] Relu_99 [Relu] inputs: [input.324 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_99 for ONNX node: Relu_99 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.328 for ONNX tensor: input.328 +[03/18/2024-15:12:40] [V] [TRT] Relu_99 [Relu] outputs: [input.328 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_100 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.328 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_100 [Conv] inputs: [input.328 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.2.reg.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.2.reg.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_100 for ONNX node: Conv_100 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: reg_2_13 for ONNX tensor: reg_2 +[03/18/2024-15:12:40] [V] [TRT] Conv_100 [Conv] outputs: [reg_2 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_101 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_878 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_879 +[03/18/2024-15:12:40] [V] [TRT] Conv_101 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_878 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_879 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_101 for ONNX node: Conv_101 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.336 for ONNX tensor: input.336 +[03/18/2024-15:12:40] [V] [TRT] Conv_101 [Conv] outputs: [input.336 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_102 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.336 +[03/18/2024-15:12:40] [V] [TRT] Relu_102 [Relu] inputs: [input.336 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_102 for ONNX node: Relu_102 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.340 for ONNX tensor: input.340 +[03/18/2024-15:12:40] [V] [TRT] Relu_102 [Relu] outputs: [input.340 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_103 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.340 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_103 [Conv] inputs: [input.340 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.2.height.3.weight -> (1, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.2.height.3.bias -> (1)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_103 for ONNX node: Conv_103 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 1 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 1, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: height_2_14 for ONNX tensor: height_2 +[03/18/2024-15:12:40] [V] [TRT] Conv_103 [Conv] outputs: [height_2 -> (1, 1, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_104 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_881 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_882 +[03/18/2024-15:12:40] [V] [TRT] Conv_104 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_881 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_882 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_104 for ONNX node: Conv_104 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.348 for ONNX tensor: input.348 +[03/18/2024-15:12:40] [V] [TRT] Conv_104 [Conv] outputs: [input.348 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_105 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.348 +[03/18/2024-15:12:40] [V] [TRT] Relu_105 [Relu] inputs: [input.348 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_105 for ONNX node: Relu_105 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.352 for ONNX tensor: input.352 +[03/18/2024-15:12:40] [V] [TRT] Relu_105 [Relu] outputs: [input.352 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_106 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.352 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_106 [Conv] inputs: [input.352 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.2.dim.3.weight -> (3, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.2.dim.3.bias -> (3)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_106 for ONNX node: Conv_106 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 3 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 3, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: dim_2_15 for ONNX tensor: dim_2 +[03/18/2024-15:12:40] [V] [TRT] Conv_106 [Conv] outputs: [dim_2 -> (1, 3, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_107 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_884 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_885 +[03/18/2024-15:12:40] [V] [TRT] Conv_107 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_884 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_885 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_107 for ONNX node: Conv_107 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.360 for ONNX tensor: input.360 +[03/18/2024-15:12:40] [V] [TRT] Conv_107 [Conv] outputs: [input.360 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_108 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.360 +[03/18/2024-15:12:40] [V] [TRT] Relu_108 [Relu] inputs: [input.360 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_108 for ONNX node: Relu_108 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.364 for ONNX tensor: input.364 +[03/18/2024-15:12:40] [V] [TRT] Relu_108 [Relu] outputs: [input.364 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_109 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.364 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_109 [Conv] inputs: [input.364 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.2.rot.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.2.rot.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_109 for ONNX node: Conv_109 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: rot_2_16 for ONNX tensor: rot_2 +[03/18/2024-15:12:40] [V] [TRT] Conv_109 [Conv] outputs: [rot_2 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_110 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_887 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_888 +[03/18/2024-15:12:40] [V] [TRT] Conv_110 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_887 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_888 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_110 for ONNX node: Conv_110 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.372 for ONNX tensor: input.372 +[03/18/2024-15:12:40] [V] [TRT] Conv_110 [Conv] outputs: [input.372 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_111 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.372 +[03/18/2024-15:12:40] [V] [TRT] Relu_111 [Relu] inputs: [input.372 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_111 for ONNX node: Relu_111 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.376 for ONNX tensor: input.376 +[03/18/2024-15:12:40] [V] [TRT] Relu_111 [Relu] outputs: [input.376 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_112 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.376 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_112 [Conv] inputs: [input.376 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.2.vel.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.2.vel.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_112 for ONNX node: Conv_112 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: vel_2_17 for ONNX tensor: vel_2 +[03/18/2024-15:12:40] [V] [TRT] Conv_112 [Conv] outputs: [vel_2 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_113 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_890 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_891 +[03/18/2024-15:12:40] [V] [TRT] Conv_113 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_890 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_891 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_113 for ONNX node: Conv_113 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.384 for ONNX tensor: input.384 +[03/18/2024-15:12:40] [V] [TRT] Conv_113 [Conv] outputs: [input.384 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_114 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.384 +[03/18/2024-15:12:40] [V] [TRT] Relu_114 [Relu] inputs: [input.384 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_114 for ONNX node: Relu_114 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.388 for ONNX tensor: input.388 +[03/18/2024-15:12:40] [V] [TRT] Relu_114 [Relu] outputs: [input.388 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_115 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.388 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.2.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_115 [Conv] inputs: [input.388 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.2.hm.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.2.hm.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_115 for ONNX node: Conv_115 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: hm_2_18 for ONNX tensor: hm_2 +[03/18/2024-15:12:40] [V] [TRT] Conv_115 [Conv] outputs: [hm_2 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_116 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_893 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_894 +[03/18/2024-15:12:40] [V] [TRT] Conv_116 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_893 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_894 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_116 for ONNX node: Conv_116 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.396 for ONNX tensor: input.396 +[03/18/2024-15:12:40] [V] [TRT] Conv_116 [Conv] outputs: [input.396 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_117 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.396 +[03/18/2024-15:12:40] [V] [TRT] Relu_117 [Relu] inputs: [input.396 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_117 for ONNX node: Relu_117 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.400 for ONNX tensor: input.400 +[03/18/2024-15:12:40] [V] [TRT] Relu_117 [Relu] outputs: [input.400 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_118 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.400 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_118 [Conv] inputs: [input.400 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.3.reg.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.3.reg.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_118 for ONNX node: Conv_118 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: reg_3_19 for ONNX tensor: reg_3 +[03/18/2024-15:12:40] [V] [TRT] Conv_118 [Conv] outputs: [reg_3 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_119 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_896 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_897 +[03/18/2024-15:12:40] [V] [TRT] Conv_119 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_896 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_897 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_119 for ONNX node: Conv_119 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.408 for ONNX tensor: input.408 +[03/18/2024-15:12:40] [V] [TRT] Conv_119 [Conv] outputs: [input.408 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_120 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.408 +[03/18/2024-15:12:40] [V] [TRT] Relu_120 [Relu] inputs: [input.408 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_120 for ONNX node: Relu_120 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.412 for ONNX tensor: input.412 +[03/18/2024-15:12:40] [V] [TRT] Relu_120 [Relu] outputs: [input.412 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_121 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.412 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_121 [Conv] inputs: [input.412 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.3.height.3.weight -> (1, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.3.height.3.bias -> (1)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_121 for ONNX node: Conv_121 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 1 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 1, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: height_3_20 for ONNX tensor: height_3 +[03/18/2024-15:12:40] [V] [TRT] Conv_121 [Conv] outputs: [height_3 -> (1, 1, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_122 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_899 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_900 +[03/18/2024-15:12:40] [V] [TRT] Conv_122 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_899 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_900 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_122 for ONNX node: Conv_122 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.420 for ONNX tensor: input.420 +[03/18/2024-15:12:40] [V] [TRT] Conv_122 [Conv] outputs: [input.420 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_123 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.420 +[03/18/2024-15:12:40] [V] [TRT] Relu_123 [Relu] inputs: [input.420 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_123 for ONNX node: Relu_123 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.424 for ONNX tensor: input.424 +[03/18/2024-15:12:40] [V] [TRT] Relu_123 [Relu] outputs: [input.424 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_124 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.424 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_124 [Conv] inputs: [input.424 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.3.dim.3.weight -> (3, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.3.dim.3.bias -> (3)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_124 for ONNX node: Conv_124 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 3 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 3, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: dim_3_21 for ONNX tensor: dim_3 +[03/18/2024-15:12:40] [V] [TRT] Conv_124 [Conv] outputs: [dim_3 -> (1, 3, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_125 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_902 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_903 +[03/18/2024-15:12:40] [V] [TRT] Conv_125 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_902 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_903 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_125 for ONNX node: Conv_125 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.432 for ONNX tensor: input.432 +[03/18/2024-15:12:40] [V] [TRT] Conv_125 [Conv] outputs: [input.432 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_126 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.432 +[03/18/2024-15:12:40] [V] [TRT] Relu_126 [Relu] inputs: [input.432 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_126 for ONNX node: Relu_126 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.436 for ONNX tensor: input.436 +[03/18/2024-15:12:40] [V] [TRT] Relu_126 [Relu] outputs: [input.436 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_127 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.436 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_127 [Conv] inputs: [input.436 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.3.rot.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.3.rot.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_127 for ONNX node: Conv_127 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: rot_3_22 for ONNX tensor: rot_3 +[03/18/2024-15:12:40] [V] [TRT] Conv_127 [Conv] outputs: [rot_3 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_128 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_905 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_906 +[03/18/2024-15:12:40] [V] [TRT] Conv_128 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_905 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_906 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_128 for ONNX node: Conv_128 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.444 for ONNX tensor: input.444 +[03/18/2024-15:12:40] [V] [TRT] Conv_128 [Conv] outputs: [input.444 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_129 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.444 +[03/18/2024-15:12:40] [V] [TRT] Relu_129 [Relu] inputs: [input.444 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_129 for ONNX node: Relu_129 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.448 for ONNX tensor: input.448 +[03/18/2024-15:12:40] [V] [TRT] Relu_129 [Relu] outputs: [input.448 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_130 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.448 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_130 [Conv] inputs: [input.448 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.3.vel.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.3.vel.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_130 for ONNX node: Conv_130 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: vel_3_23 for ONNX tensor: vel_3 +[03/18/2024-15:12:40] [V] [TRT] Conv_130 [Conv] outputs: [vel_3 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_131 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_908 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_909 +[03/18/2024-15:12:40] [V] [TRT] Conv_131 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_908 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_909 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_131 for ONNX node: Conv_131 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.456 for ONNX tensor: input.456 +[03/18/2024-15:12:40] [V] [TRT] Conv_131 [Conv] outputs: [input.456 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_132 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.456 +[03/18/2024-15:12:40] [V] [TRT] Relu_132 [Relu] inputs: [input.456 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_132 for ONNX node: Relu_132 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.460 for ONNX tensor: input.460 +[03/18/2024-15:12:40] [V] [TRT] Relu_132 [Relu] outputs: [input.460 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_133 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.460 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.3.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_133 [Conv] inputs: [input.460 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.3.hm.3.weight -> (1, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.3.hm.3.bias -> (1)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_133 for ONNX node: Conv_133 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 1 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 1, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: hm_3_24 for ONNX tensor: hm_3 +[03/18/2024-15:12:40] [V] [TRT] Conv_133 [Conv] outputs: [hm_3 -> (1, 1, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_134 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_911 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_912 +[03/18/2024-15:12:40] [V] [TRT] Conv_134 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_911 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_912 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_134 for ONNX node: Conv_134 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.468 for ONNX tensor: input.468 +[03/18/2024-15:12:40] [V] [TRT] Conv_134 [Conv] outputs: [input.468 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_135 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.468 +[03/18/2024-15:12:40] [V] [TRT] Relu_135 [Relu] inputs: [input.468 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_135 for ONNX node: Relu_135 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.472 for ONNX tensor: input.472 +[03/18/2024-15:12:40] [V] [TRT] Relu_135 [Relu] outputs: [input.472 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_136 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.472 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_136 [Conv] inputs: [input.472 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.4.reg.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.4.reg.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_136 for ONNX node: Conv_136 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: reg_4_25 for ONNX tensor: reg_4 +[03/18/2024-15:12:40] [V] [TRT] Conv_136 [Conv] outputs: [reg_4 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_137 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_914 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_915 +[03/18/2024-15:12:40] [V] [TRT] Conv_137 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_914 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_915 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_137 for ONNX node: Conv_137 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.480 for ONNX tensor: input.480 +[03/18/2024-15:12:40] [V] [TRT] Conv_137 [Conv] outputs: [input.480 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_138 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.480 +[03/18/2024-15:12:40] [V] [TRT] Relu_138 [Relu] inputs: [input.480 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_138 for ONNX node: Relu_138 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.484 for ONNX tensor: input.484 +[03/18/2024-15:12:40] [V] [TRT] Relu_138 [Relu] outputs: [input.484 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_139 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.484 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_139 [Conv] inputs: [input.484 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.4.height.3.weight -> (1, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.4.height.3.bias -> (1)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_139 for ONNX node: Conv_139 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 1 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 1, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: height_4_26 for ONNX tensor: height_4 +[03/18/2024-15:12:40] [V] [TRT] Conv_139 [Conv] outputs: [height_4 -> (1, 1, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_140 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_917 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_918 +[03/18/2024-15:12:40] [V] [TRT] Conv_140 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_917 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_918 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_140 for ONNX node: Conv_140 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.492 for ONNX tensor: input.492 +[03/18/2024-15:12:40] [V] [TRT] Conv_140 [Conv] outputs: [input.492 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_141 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.492 +[03/18/2024-15:12:40] [V] [TRT] Relu_141 [Relu] inputs: [input.492 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_141 for ONNX node: Relu_141 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.496 for ONNX tensor: input.496 +[03/18/2024-15:12:40] [V] [TRT] Relu_141 [Relu] outputs: [input.496 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_142 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.496 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_142 [Conv] inputs: [input.496 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.4.dim.3.weight -> (3, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.4.dim.3.bias -> (3)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_142 for ONNX node: Conv_142 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 3 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 3, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: dim_4_27 for ONNX tensor: dim_4 +[03/18/2024-15:12:40] [V] [TRT] Conv_142 [Conv] outputs: [dim_4 -> (1, 3, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_143 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_920 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_921 +[03/18/2024-15:12:40] [V] [TRT] Conv_143 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_920 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_921 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_143 for ONNX node: Conv_143 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.504 for ONNX tensor: input.504 +[03/18/2024-15:12:40] [V] [TRT] Conv_143 [Conv] outputs: [input.504 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_144 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.504 +[03/18/2024-15:12:40] [V] [TRT] Relu_144 [Relu] inputs: [input.504 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_144 for ONNX node: Relu_144 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.508 for ONNX tensor: input.508 +[03/18/2024-15:12:40] [V] [TRT] Relu_144 [Relu] outputs: [input.508 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_145 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.508 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_145 [Conv] inputs: [input.508 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.4.rot.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.4.rot.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_145 for ONNX node: Conv_145 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: rot_4_28 for ONNX tensor: rot_4 +[03/18/2024-15:12:40] [V] [TRT] Conv_145 [Conv] outputs: [rot_4 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_146 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_923 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_924 +[03/18/2024-15:12:40] [V] [TRT] Conv_146 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_923 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_924 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_146 for ONNX node: Conv_146 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.516 for ONNX tensor: input.516 +[03/18/2024-15:12:40] [V] [TRT] Conv_146 [Conv] outputs: [input.516 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_147 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.516 +[03/18/2024-15:12:40] [V] [TRT] Relu_147 [Relu] inputs: [input.516 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_147 for ONNX node: Relu_147 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.520 for ONNX tensor: input.520 +[03/18/2024-15:12:40] [V] [TRT] Relu_147 [Relu] outputs: [input.520 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_148 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.520 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_148 [Conv] inputs: [input.520 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.4.vel.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.4.vel.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_148 for ONNX node: Conv_148 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: vel_4_29 for ONNX tensor: vel_4 +[03/18/2024-15:12:40] [V] [TRT] Conv_148 [Conv] outputs: [vel_4 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_149 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_926 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_927 +[03/18/2024-15:12:40] [V] [TRT] Conv_149 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_926 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_927 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_149 for ONNX node: Conv_149 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.528 for ONNX tensor: input.528 +[03/18/2024-15:12:40] [V] [TRT] Conv_149 [Conv] outputs: [input.528 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_150 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.528 +[03/18/2024-15:12:40] [V] [TRT] Relu_150 [Relu] inputs: [input.528 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_150 for ONNX node: Relu_150 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.532 for ONNX tensor: input.532 +[03/18/2024-15:12:40] [V] [TRT] Relu_150 [Relu] outputs: [input.532 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_151 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.532 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.4.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_151 [Conv] inputs: [input.532 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.4.hm.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.4.hm.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_151 for ONNX node: Conv_151 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: hm_4_30 for ONNX tensor: hm_4 +[03/18/2024-15:12:40] [V] [TRT] Conv_151 [Conv] outputs: [hm_4 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_152 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_929 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_930 +[03/18/2024-15:12:40] [V] [TRT] Conv_152 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_929 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_930 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_152 for ONNX node: Conv_152 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.540 for ONNX tensor: input.540 +[03/18/2024-15:12:40] [V] [TRT] Conv_152 [Conv] outputs: [input.540 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_153 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.540 +[03/18/2024-15:12:40] [V] [TRT] Relu_153 [Relu] inputs: [input.540 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_153 for ONNX node: Relu_153 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.544 for ONNX tensor: input.544 +[03/18/2024-15:12:40] [V] [TRT] Relu_153 [Relu] outputs: [input.544 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_154 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.544 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.reg.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.reg.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_154 [Conv] inputs: [input.544 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.5.reg.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.5.reg.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_154 for ONNX node: Conv_154 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: reg_5_31 for ONNX tensor: reg_5 +[03/18/2024-15:12:40] [V] [TRT] Conv_154 [Conv] outputs: [reg_5 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_155 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_932 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_933 +[03/18/2024-15:12:40] [V] [TRT] Conv_155 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_932 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_933 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_155 for ONNX node: Conv_155 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.552 for ONNX tensor: input.552 +[03/18/2024-15:12:40] [V] [TRT] Conv_155 [Conv] outputs: [input.552 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_156 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.552 +[03/18/2024-15:12:40] [V] [TRT] Relu_156 [Relu] inputs: [input.552 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_156 for ONNX node: Relu_156 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.556 for ONNX tensor: input.556 +[03/18/2024-15:12:40] [V] [TRT] Relu_156 [Relu] outputs: [input.556 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_157 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.556 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.height.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.height.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_157 [Conv] inputs: [input.556 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.5.height.3.weight -> (1, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.5.height.3.bias -> (1)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_157 for ONNX node: Conv_157 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 1 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 1, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: height_5_32 for ONNX tensor: height_5 +[03/18/2024-15:12:40] [V] [TRT] Conv_157 [Conv] outputs: [height_5 -> (1, 1, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_158 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_935 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_936 +[03/18/2024-15:12:40] [V] [TRT] Conv_158 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_935 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_936 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_158 for ONNX node: Conv_158 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.564 for ONNX tensor: input.564 +[03/18/2024-15:12:40] [V] [TRT] Conv_158 [Conv] outputs: [input.564 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_159 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.564 +[03/18/2024-15:12:40] [V] [TRT] Relu_159 [Relu] inputs: [input.564 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_159 for ONNX node: Relu_159 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.568 for ONNX tensor: input.568 +[03/18/2024-15:12:40] [V] [TRT] Relu_159 [Relu] outputs: [input.568 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_160 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.568 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.dim.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.dim.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_160 [Conv] inputs: [input.568 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.5.dim.3.weight -> (3, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.5.dim.3.bias -> (3)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_160 for ONNX node: Conv_160 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 3 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 3, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: dim_5_33 for ONNX tensor: dim_5 +[03/18/2024-15:12:40] [V] [TRT] Conv_160 [Conv] outputs: [dim_5 -> (1, 3, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_161 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_938 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_939 +[03/18/2024-15:12:40] [V] [TRT] Conv_161 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_938 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_939 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_161 for ONNX node: Conv_161 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.576 for ONNX tensor: input.576 +[03/18/2024-15:12:40] [V] [TRT] Conv_161 [Conv] outputs: [input.576 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_162 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.576 +[03/18/2024-15:12:40] [V] [TRT] Relu_162 [Relu] inputs: [input.576 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_162 for ONNX node: Relu_162 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.580 for ONNX tensor: input.580 +[03/18/2024-15:12:40] [V] [TRT] Relu_162 [Relu] outputs: [input.580 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_163 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.580 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.rot.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.rot.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_163 [Conv] inputs: [input.580 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.5.rot.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.5.rot.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_163 for ONNX node: Conv_163 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: rot_5_34 for ONNX tensor: rot_5 +[03/18/2024-15:12:40] [V] [TRT] Conv_163 [Conv] outputs: [rot_5 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_164 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_941 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_942 +[03/18/2024-15:12:40] [V] [TRT] Conv_164 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_941 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_942 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_164 for ONNX node: Conv_164 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.588 for ONNX tensor: input.588 +[03/18/2024-15:12:40] [V] [TRT] Conv_164 [Conv] outputs: [input.588 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_165 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.588 +[03/18/2024-15:12:40] [V] [TRT] Relu_165 [Relu] inputs: [input.588 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_165 for ONNX node: Relu_165 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.592 for ONNX tensor: input.592 +[03/18/2024-15:12:40] [V] [TRT] Relu_165 [Relu] outputs: [input.592 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_166 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.592 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.vel.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.vel.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_166 [Conv] inputs: [input.592 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.5.vel.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.5.vel.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_166 for ONNX node: Conv_166 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: vel_5_35 for ONNX tensor: vel_5 +[03/18/2024-15:12:40] [V] [TRT] Conv_166 [Conv] outputs: [vel_5 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_167 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_651 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_944 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: onnx::Conv_945 +[03/18/2024-15:12:40] [V] [TRT] Conv_167 [Conv] inputs: [onnx::Conv_651 -> (1, 64, 180, 180)[FLOAT]], [onnx::Conv_944 -> (64, 64, 3, 3)[FLOAT]], [onnx::Conv_945 -> (64)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_167 for ONNX node: Conv_167 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 64 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.600 for ONNX tensor: input.600 +[03/18/2024-15:12:40] [V] [TRT] Conv_167 [Conv] outputs: [input.600 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Relu_168 [Relu] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.600 +[03/18/2024-15:12:40] [V] [TRT] Relu_168 [Relu] inputs: [input.600 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Relu_168 for ONNX node: Relu_168 +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: input.604 for ONNX tensor: input.604 +[03/18/2024-15:12:40] [V] [TRT] Relu_168 [Relu] outputs: [input.604 -> (1, 64, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Parsing node: Conv_169 [Conv] +[03/18/2024-15:12:40] [V] [TRT] Searching for input: input.604 +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.hm.3.weight +[03/18/2024-15:12:40] [V] [TRT] Searching for input: model.bbox_head.tasks.5.hm.3.bias +[03/18/2024-15:12:40] [V] [TRT] Conv_169 [Conv] inputs: [input.604 -> (1, 64, 180, 180)[FLOAT]], [model.bbox_head.tasks.5.hm.3.weight -> (2, 64, 3, 3)[FLOAT]], [model.bbox_head.tasks.5.hm.3.bias -> (2)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Convolution input dimensions: (1, 64, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering layer: Conv_169 for ONNX node: Conv_169 +[03/18/2024-15:12:40] [V] [TRT] Using kernel: (3, 3), strides: (1, 1), prepadding: (1, 1), postpadding: (1, 1), dilations: (1, 1), numOutputs: 2 +[03/18/2024-15:12:40] [V] [TRT] Convolution output dimensions: (1, 2, 180, 180) +[03/18/2024-15:12:40] [V] [TRT] Registering tensor: hm_5_36 for ONNX tensor: hm_5 +[03/18/2024-15:12:40] [V] [TRT] Conv_169 [Conv] outputs: [hm_5 -> (1, 2, 180, 180)[FLOAT]], +[03/18/2024-15:12:40] [V] [TRT] Marking reg_0_1 as output: reg_0 +[03/18/2024-15:12:40] [V] [TRT] Marking height_0_2 as output: height_0 +[03/18/2024-15:12:40] [V] [TRT] Marking dim_0_3 as output: dim_0 +[03/18/2024-15:12:40] [V] [TRT] Marking rot_0_4 as output: rot_0 +[03/18/2024-15:12:40] [V] [TRT] Marking vel_0_5 as output: vel_0 +[03/18/2024-15:12:40] [V] [TRT] Marking hm_0_6 as output: hm_0 +[03/18/2024-15:12:40] [V] [TRT] Marking reg_1_7 as output: reg_1 +[03/18/2024-15:12:40] [V] [TRT] Marking height_1_8 as output: height_1 +[03/18/2024-15:12:40] [V] [TRT] Marking dim_1_9 as output: dim_1 +[03/18/2024-15:12:40] [V] [TRT] Marking rot_1_10 as output: rot_1 +[03/18/2024-15:12:40] [V] [TRT] Marking vel_1_11 as output: vel_1 +[03/18/2024-15:12:40] [V] [TRT] Marking hm_1_12 as output: hm_1 +[03/18/2024-15:12:40] [V] [TRT] Marking reg_2_13 as output: reg_2 +[03/18/2024-15:12:40] [V] [TRT] Marking height_2_14 as output: height_2 +[03/18/2024-15:12:40] [V] [TRT] Marking dim_2_15 as output: dim_2 +[03/18/2024-15:12:40] [V] [TRT] Marking rot_2_16 as output: rot_2 +[03/18/2024-15:12:40] [V] [TRT] Marking vel_2_17 as output: vel_2 +[03/18/2024-15:12:40] [V] [TRT] Marking hm_2_18 as output: hm_2 +[03/18/2024-15:12:40] [V] [TRT] Marking reg_3_19 as output: reg_3 +[03/18/2024-15:12:40] [V] [TRT] Marking height_3_20 as output: height_3 +[03/18/2024-15:12:40] [V] [TRT] Marking dim_3_21 as output: dim_3 +[03/18/2024-15:12:40] [V] [TRT] Marking rot_3_22 as output: rot_3 +[03/18/2024-15:12:40] [V] [TRT] Marking vel_3_23 as output: vel_3 +[03/18/2024-15:12:40] [V] [TRT] Marking hm_3_24 as output: hm_3 +[03/18/2024-15:12:40] [V] [TRT] Marking reg_4_25 as output: reg_4 +[03/18/2024-15:12:40] [V] [TRT] Marking height_4_26 as output: height_4 +[03/18/2024-15:12:40] [V] [TRT] Marking dim_4_27 as output: dim_4 +[03/18/2024-15:12:40] [V] [TRT] Marking rot_4_28 as output: rot_4 +[03/18/2024-15:12:40] [V] [TRT] Marking vel_4_29 as output: vel_4 +[03/18/2024-15:12:40] [V] [TRT] Marking hm_4_30 as output: hm_4 +[03/18/2024-15:12:40] [V] [TRT] Marking reg_5_31 as output: reg_5 +[03/18/2024-15:12:40] [V] [TRT] Marking height_5_32 as output: height_5 +[03/18/2024-15:12:40] [V] [TRT] Marking dim_5_33 as output: dim_5 +[03/18/2024-15:12:40] [V] [TRT] Marking rot_5_34 as output: rot_5 +[03/18/2024-15:12:40] [V] [TRT] Marking vel_5_35 as output: vel_5 +[03/18/2024-15:12:40] [V] [TRT] Marking hm_5_36 as output: hm_5 +[03/18/2024-15:12:40] [I] Finish parsing network model +[03/18/2024-15:12:40] [V] [TRT] Original: 140 layers +[03/18/2024-15:12:40] [V] [TRT] After dead-layer removal: 140 layers +[03/18/2024-15:12:40] [V] [TRT] Applying generic optimizations to the graph for inference. +[03/18/2024-15:12:40] [V] [TRT] After Myelin optimization: 140 layers +[03/18/2024-15:12:40] [V] [TRT] Applying ScaleNodes fusions. +[03/18/2024-15:12:40] [V] [TRT] After scale fusion: 140 layers +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_15 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_15 with Relu_16 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_17 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_17 with Relu_18 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_19 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_19 with Relu_20 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_21 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_21 with Relu_22 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_23 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_23 with Relu_24 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_25 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_25 with Relu_26 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_27 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_27 with Relu_28 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_44 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_44 with Relu_45 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_46 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_46 with Relu_47 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_48 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_48 with Relu_49 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_50 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_50 with Relu_51 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_52 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_52 with Relu_53 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_54 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_54 with Relu_55 +[03/18/2024-15:12:40] [V] [TRT] Running: DeconvScaleFusion on ConvTranspose_56 +[03/18/2024-15:12:40] [V] [TRT] DeconvScaleFusion: Fusing ConvTranspose_56 with BatchNormalization_57 +[03/18/2024-15:12:40] [V] [TRT] Running: DeconvReluClipReluFusion on ConvTranspose_56 + BatchNormalization_57 +[03/18/2024-15:12:40] [V] [TRT] DeconvReluClipReluFusion: Fusing ConvTranspose_56 + BatchNormalization_57 with Relu_58 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_60 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_60 with Relu_61 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_62 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_62 with Relu_63 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_65 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_65 with Relu_66 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_68 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_68 with Relu_69 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_71 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_71 with Relu_72 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_74 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_74 with Relu_75 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_77 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_77 with Relu_78 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_80 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_80 with Relu_81 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_83 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_83 with Relu_84 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_86 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_86 with Relu_87 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_89 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_89 with Relu_90 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_92 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_92 with Relu_93 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_95 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_95 with Relu_96 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_98 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_98 with Relu_99 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_101 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_101 with Relu_102 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_104 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_104 with Relu_105 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_107 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_107 with Relu_108 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_110 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_110 with Relu_111 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_113 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_113 with Relu_114 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_116 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_116 with Relu_117 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_119 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_119 with Relu_120 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_122 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_122 with Relu_123 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_125 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_125 with Relu_126 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_128 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_128 with Relu_129 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_131 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_131 with Relu_132 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_134 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_134 with Relu_135 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_137 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_137 with Relu_138 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_140 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_140 with Relu_141 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_143 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_143 with Relu_144 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_146 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_146 with Relu_147 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_149 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_149 with Relu_150 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_152 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_152 with Relu_153 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_155 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_155 with Relu_156 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_158 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_158 with Relu_159 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_161 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_161 with Relu_162 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_164 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_164 with Relu_165 +[03/18/2024-15:12:40] [V] [TRT] Running: ConvReluFusion on Conv_167 +[03/18/2024-15:12:40] [V] [TRT] ConvReluFusion: Fusing Conv_167 with Relu_168 +[03/18/2024-15:12:40] [V] [TRT] After dupe layer removal: 88 layers +[03/18/2024-15:12:40] [V] [TRT] After final dead-layer removal: 88 layers +[03/18/2024-15:12:40] [V] [TRT] After tensor merging: 88 layers +[03/18/2024-15:12:40] [V] [TRT] After vertical fusions: 88 layers +[03/18/2024-15:12:40] [V] [TRT] After dupe layer removal: 88 layers +[03/18/2024-15:12:40] [V] [TRT] After final dead-layer removal: 88 layers +[03/18/2024-15:12:40] [V] [TRT] Merging layers: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 +[03/18/2024-15:12:40] [V] [TRT] Merging layers: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 +[03/18/2024-15:12:40] [V] [TRT] Merging layers: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 +[03/18/2024-15:12:40] [V] [TRT] Merging layers: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 +[03/18/2024-15:12:40] [V] [TRT] Merging layers: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 +[03/18/2024-15:12:40] [V] [TRT] After tensor merging: 57 layers +[03/18/2024-15:12:40] [V] [TRT] After slice removal: 57 layers +[03/18/2024-15:12:40] [V] [TRT] Eliminating concatenation Concat_59 +[03/18/2024-15:12:40] [V] [TRT] Retargeting onnx::Concat_602 to input.164 +[03/18/2024-15:12:40] [V] [TRT] Retargeting onnx::Concat_647 to input.164 +[03/18/2024-15:12:40] [V] [TRT] After concat removal: 56 layers +[03/18/2024-15:12:40] [V] [TRT] Trying to split Reshape and strided tensor +[03/18/2024-15:12:40] [V] [TRT] Graph construction and optimization completed in 0.100665 seconds. +[03/18/2024-15:12:40] [V] [TRT] Trying to load shared library libcublas.so.11 +[03/18/2024-15:12:40] [V] [TRT] Loaded shared library libcublas.so.11 +[03/18/2024-15:12:41] [V] [TRT] Using cublas as plugin tactic source +[03/18/2024-15:12:41] [V] [TRT] Trying to load shared library libcublasLt.so.11 +[03/18/2024-15:12:41] [V] [TRT] Loaded shared library libcublasLt.so.11 +[03/18/2024-15:12:41] [V] [TRT] Using cublasLt as core library tactic source +[03/18/2024-15:12:41] [I] [TRT] [MemUsageChange] Init cuBLAS/cuBLASLt: CPU +941, GPU +202, now: CPU 1598, GPU 1014 (MiB) +[03/18/2024-15:12:41] [V] [TRT] Trying to load shared library libcudnn.so.8 +[03/18/2024-15:12:41] [V] [TRT] Loaded shared library libcudnn.so.8 +[03/18/2024-15:12:41] [V] [TRT] Using cuDNN as plugin tactic source +[03/18/2024-15:12:41] [V] [TRT] Using cuDNN as core library tactic source +[03/18/2024-15:12:41] [I] [TRT] [MemUsageChange] Init cuDNN: CPU +579, GPU +192, now: CPU 2177, GPU 1206 (MiB) +[03/18/2024-15:12:41] [W] [TRT] TensorRT was linked against cuDNN 8.6.0 but loaded cuDNN 8.2.1 +[03/18/2024-15:12:41] [I] [TRT] Local timing cache in use. Profiling results in this builder pass will not be stored. +[03/18/2024-15:12:41] [V] [TRT] Constructing optimization profile number 0 [1/1]. +[03/18/2024-15:12:41] [V] [TRT] Reserving memory for host IO tensors. Host: 0 bytes +[03/18/2024-15:12:41] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.187831 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.204192 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.255854 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.187831 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,1,46080,256) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.338944 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.19061 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.339383 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.19061 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.446025 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.19339 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.351671 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.19339 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.215333 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.135022 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.157257 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.135022 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.340722 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.43125 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.340846 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.340722 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.387365 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129097 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.167799 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129097 +[03/18/2024-15:12:41] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.176274 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129973 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.176421 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129973 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.186222 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.136695 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.187099 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.136695 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0959771 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0964023 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.136923 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0959771 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.118126 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.108325 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0974994 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0974994 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.184759 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.096256 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.184174 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.096256 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.183625 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.096256 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.102546 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.096256 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.648485 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.130853 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.540087 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.130853 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.13707 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.132169 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.131015 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.131015 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.483621 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0971337 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.555008 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0971337 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.509952 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.1024 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.509952 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.1024 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.12288 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0968411 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.121856 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0968411 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.121929 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.096768 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.121945 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.096768 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.627712 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.131218 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.539209 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.131218 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.136923 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.133632 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.130853 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.130853 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.484206 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0971474 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.558624 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0971474 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.510245 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.101376 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.510683 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.101376 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.141883 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0972206 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.14197 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0972206 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.142336 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0966949 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.144823 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0966949 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.100645 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0982309 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.130414 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0982309 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.165157 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0974994 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.166034 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0974994 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.169838 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.104814 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.168238 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.104814 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.107813 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0669501 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.077824 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0669501 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.158427 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.216357 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.157696 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.157696 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.155794 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0663162 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0857966 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0663162 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.115931 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0994743 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.096256 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.096256 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.134656 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0970606 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.134217 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0970606 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.143506 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.104382 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.14352 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.104382 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.10101 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.244297 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0699261 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0699261 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.136777 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0718994 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.13685 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0718994 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.136777 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0719954 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0814811 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0719954 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.488594 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.104594 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.550619 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.104594 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.125209 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.09728 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.123831 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.09728 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.143214 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0985189 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.14336 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0985189 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.416622 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.213285 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.416768 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.213285 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.449536 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.096256 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.446757 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.096256 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.129177 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0690804 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.129243 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0690804 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.489033 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0979383 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0954514 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0954514 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.125367 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0985966 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.125221 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0985966 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.144969 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0969874 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.150089 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0969874 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.511707 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.213138 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0662674 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0662674 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.446432 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0958171 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0683154 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0683154 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.12 -> ) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.128585 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0655848 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.128585 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0655848 +[03/18/2024-15:12:41] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.167936 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.132331 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.168229 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.132331 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.176567 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129609 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.177445 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129609 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0957531 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.096256 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.126098 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0957531 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.109575 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.101522 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0964023 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0964023 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.169399 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0960343 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.169138 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0960343 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.17013 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0970766 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0974263 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0970766 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.174665 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0961097 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.174505 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0961097 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.716654 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.131438 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.541111 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.131438 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.130779 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.134071 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.131438 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.130779 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.483767 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0970606 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.482158 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0970606 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.655945 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.100133 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.507465 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.100133 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.119881 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.102345 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.120693 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.102345 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.120905 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0965486 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.120747 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0965486 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.120759 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0974263 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.118638 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0974263 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.535698 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.130487 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.729819 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.130487 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.130487 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129975 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.130267 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129975 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.550034 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0980114 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.482743 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0980114 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.510683 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0997669 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.643803 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0997669 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.138313 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0966194 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.144823 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0966194 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.144677 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.10051 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.144677 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.10051 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.144823 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0969143 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.144677 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0969143 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0955246 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0974903 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.126302 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0955246 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.161646 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0986697 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.162085 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0986697 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.167643 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0972091 +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.167465 +[03/18/2024-15:12:41] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0972091 +[03/18/2024-15:12:41] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:41] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:41] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.106862 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.067389 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0773851 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.067389 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.154478 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.21109 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.154624 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.154478 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.154624 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0660236 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0856503 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0660236 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.155063 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.066653 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.157111 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.066653 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.116663 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0986697 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0961028 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0961028 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.140046 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0989623 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.136777 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0989623 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.147017 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.09728 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.14731 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.09728 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.104448 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.252635 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0693882 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0693882 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.135088 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0724114 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.138094 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0724114 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.13824 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0728503 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0817737 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0728503 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.137947 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0726423 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.138094 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0726423 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.500151 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0992389 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.489911 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0992389 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.128293 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0974903 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.128222 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0974903 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.150821 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0987429 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.150821 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0987429 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.418085 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.224736 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.417646 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.224736 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.556617 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.102693 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.447488 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.102693 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.137874 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.066557 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.137874 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.066557 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.137801 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0660754 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.13568 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0660754 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.617723 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.101742 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0958263 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0958263 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.125074 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0970606 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.123392 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0970606 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.144823 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0985966 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.144677 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0985966 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.416914 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.211529 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0667063 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0667063 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.54272 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.100352 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0663238 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0663238 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.131145 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0657889 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.130999 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0657889 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> input.72) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.129609 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0660236 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.128 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0660236 +[03/18/2024-15:12:42] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.173641 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0964023 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.173787 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0964023 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.116736 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0974994 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.120834 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0974994 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.141751 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0966217 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.14219 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0966217 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.159598 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0668891 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.160329 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0668891 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.142043 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0746057 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.14205 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0746057 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.13859 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0668038 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.138679 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0668038 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(259200,1:16,1440,8) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.14336 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.068413 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.147895 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.068413 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.598432 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.099328 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.489765 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.099328 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.133925 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.103803 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.132096 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.103803 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.155648 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0976457 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.155794 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0976457 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.420425 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.227767 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.419401 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.227767 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.449097 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.10496 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.448206 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.10496 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.140727 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0682667 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.150382 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0682667 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.72 -> ) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.150235 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0688884 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.150382 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0688884 +[03/18/2024-15:12:42] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.477915 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.259657 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.396987 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.259657 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.405065 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.374053 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.478647 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.374053 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.189294 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.239323 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.187392 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.187392 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.246199 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.191634 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.281893 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.191634 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.400384 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.186807 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.3432 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.186807 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.412233 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189733 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.387657 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189733 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.388238 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187817 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.386487 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187817 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.42074 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.253952 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.39382 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.253952 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.259657 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.369225 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.328558 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.259657 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.13036 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189147 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.17936 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189147 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.4162 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.200704 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.34889 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.200704 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.23552 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187977 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.233618 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187977 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.233472 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.197047 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.233472 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.197047 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.233618 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187685 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.233472 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187685 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.4734 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.257463 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.41942 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.257463 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.259072 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.253806 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.257755 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.253806 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.16971 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.19061 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.20409 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.19061 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.25558 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.193243 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.29961 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.193243 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.379611 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189294 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.277358 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189294 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.277358 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187538 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.332069 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187538 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.452901 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189294 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.285842 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189294 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.188416 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.221495 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.187977 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.187977 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.41077 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.192219 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.338798 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.192219 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.34917 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190171 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.479525 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190171 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.214309 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129317 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.214162 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129317 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.347429 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.520046 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.346551 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.346551 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.346405 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.128379 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.350793 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.128379 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.355621 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.128279 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.356498 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.128279 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.254245 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.198217 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.255561 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.198217 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.291726 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.191634 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.291547 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.191634 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.445879 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.20011 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.327387 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.20011 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.239909 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.587045 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.371273 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.239909 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.30837 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.157527 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.301202 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.157527 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.299886 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.1536 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.166587 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.1536 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.372882 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.153454 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.299739 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.153454 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.16986 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.206702 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.32726 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.206702 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.304567 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190171 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.256293 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190171 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.302665 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.191195 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.399506 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.191195 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.02079 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.434322 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.99022 +[03/18/2024-15:12:42] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.434322 +[03/18/2024-15:12:42] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:42] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.20774 +[03/18/2024-15:12:42] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.19339 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.04171 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.19339 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.258633 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.130487 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.260087 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.130487 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.260096 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.126903 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.260096 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.126903 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.26041 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.208311 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.20699 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.208311 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.243008 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189879 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.242981 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189879 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.284379 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.197047 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.284233 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.197047 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.95964 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.428357 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.07726 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.428357 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.14616 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.191342 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.128366 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.128366 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.363959 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.127634 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.261266 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.127634 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.257463 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.12645 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.418094 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.12645 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.18627 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.212553 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.13855 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.212553 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.243986 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190025 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.244005 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190025 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.406674 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.192805 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.284379 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.192805 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.93156 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.449975 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.09452 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.449975 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.07565 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.204361 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.97705 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.204361 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.392046 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129024 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.275145 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129024 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.275017 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.128658 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.367031 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.128658 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.254391 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.253499 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.250021 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.250021 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.47221 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.467067 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.392631 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.392631 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.400238 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.337335 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.533797 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.337335 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.190171 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.230231 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.187685 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.187685 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.32389 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.22411 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.198363 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.198363 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.411794 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187977 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.412997 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187977 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.409161 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190025 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.195877 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190025 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.410917 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187831 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.491067 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187831 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.25777 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.257317 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.31775 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.257317 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.255854 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.254066 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.420571 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.254066 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.262583 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.255707 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.260535 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.255707 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.96462 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.188123 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.93098 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.188123 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.17 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.196315 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.05239 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.196315 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.238007 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.188677 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.236837 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.188677 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.23669 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187392 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.333678 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187392 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.302962 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.188855 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.23669 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.188855 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.29157 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.338674 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.05444 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.338674 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.269751 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.256754 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.257902 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.256754 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.279991 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.253952 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.28453 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.253952 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.86105 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189586 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.1384 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189586 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.12992 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.195145 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.19268 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.195145 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.277358 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187493 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.276626 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187493 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.275895 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189147 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.276041 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189147 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.276041 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.186953 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.375813 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.186953 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.191049 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.22485 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.188105 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.188105 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.432859 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.194853 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.474843 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.194853 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.351232 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190464 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.350208 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190464 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.127271 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.167173 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.12939 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.127271 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.215333 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.132315 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.156379 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.132315 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.337042 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.423351 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.337481 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.337042 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.33675 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.128073 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.171008 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.128073 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.428325 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.128878 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.338944 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.128878 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.242688 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.192951 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.25717 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.192951 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.29301 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.192951 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.292425 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.192951 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.324462 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.191927 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.324462 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.191927 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.233179 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.570514 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.233326 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.233179 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.134437 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.235808 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.128523 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.128523 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.308224 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.157403 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.368347 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.157403 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.308224 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.157696 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.16896 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.157696 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.305577 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.155648 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.304713 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.155648 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.2051 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.191195 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.17116 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.191195 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.271945 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190757 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.271945 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190757 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.486519 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.192658 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.316416 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.192658 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.959049 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.57344 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.954514 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.57344 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.21285 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.20683 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.2623 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.20683 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.284087 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129902 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.355598 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129902 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.282455 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.134363 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.282478 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.134363 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.282478 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129536 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.278089 +[03/18/2024-15:12:43] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129536 +[03/18/2024-15:12:43] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:43] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.18608 +[03/18/2024-15:12:43] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190464 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.22309 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190464 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.255269 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190025 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.255122 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190025 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.30091 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.192786 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.296393 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.192786 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.949691 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.547986 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.956416 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.547986 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.25001 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.208014 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.12917 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.12917 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.279552 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129248 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.279698 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129248 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.279552 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.12939 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.365568 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.12939 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.352256 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129829 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.279662 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129829 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.07008 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.192366 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.07652 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.192366 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.248978 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189879 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.270629 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189879 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.320073 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190587 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.395557 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190587 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.16122 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.44939 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.10972 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.44939 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.0108 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.209627 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.18345 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.209627 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.280137 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129829 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.401993 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129829 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.28277 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.130048 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.344795 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.130048 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Concat_602) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.347867 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129541 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.278089 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129541 +[03/18/2024-15:12:44] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1,23040,128) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400:2,180,1) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:4,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:8,2880,16) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:16,1440,8) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:44] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0962651 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0682621 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0957189 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0682621 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.09984 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0686568 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0965486 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0686568 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0506133 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0503832 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0705585 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0503832 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0602209 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0571429 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0515901 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0515901 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0947931 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0511025 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0928183 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0511025 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0926743 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0506636 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0515764 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0506636 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.109934 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0701196 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.106581 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0701196 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0671939 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0675291 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0676328 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0671939 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.10101 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0551497 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.10144 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0551497 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.106569 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0554362 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.106482 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0554362 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0638156 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0506636 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0638324 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0506636 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0632442 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0506636 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0632442 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0506636 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.109275 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0704122 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.109349 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0704122 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0674377 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0730697 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0673859 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0673859 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.100718 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0539794 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.100571 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0539794 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.10563 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0541745 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.105838 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0541745 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.073216 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0508541 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.07424 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0508541 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.07424 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0507611 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.074224 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0507611 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0490057 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0533562 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.066848 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0490057 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.084992 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0520777 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0836023 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0520777 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0885029 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0514438 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0882103 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0514438 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.05632 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0379246 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0408423 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0379246 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0836754 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.110811 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.08192 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.08192 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0818469 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0362057 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0462686 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0362057 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0603611 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0594408 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0504244 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0504244 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0710461 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0513021 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.070656 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0513021 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0754834 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0520777 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0754834 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0520777 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0540678 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.159305 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0380423 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0380423 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0693989 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0392777 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0695345 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0392777 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0694888 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0380709 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0425623 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0380709 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0857966 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0549562 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0856709 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0549562 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0623665 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0515246 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0623177 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0515246 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0724114 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0509592 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0725577 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0509592 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.079856 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.139995 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0797257 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0797257 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0883566 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0513813 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0883566 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0513813 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0677303 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0357589 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0676404 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0357589 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0863817 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0555398 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0496808 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0496808 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0630004 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.051395 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0627566 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.051395 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0729966 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0511939 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0784823 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0511939 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.084992 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.148334 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0363451 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0363451 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0940617 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0555398 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0354889 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0354889 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.96 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.072704 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0365383 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.072704 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0365383 +[03/18/2024-15:12:44] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,8100,90,1) -> Half(129600,1:16,1440,16) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.102267 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.051005 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0991086 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.051005 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,23040,256) -> Half(129600,1:16,1440,16) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0654278 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0507611 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0654872 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0507611 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,5760,64) -> Half(129600,1:16,1440,16) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0764457 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0507611 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0765074 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0507611 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,8100,90,1) -> Half(129600,1:16,1440,16) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0808229 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0373394 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0806034 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0373394 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,8100:2,90,1) -> Half(129600,1:16,1440,16) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0689981 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0379703 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0689493 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0379703 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,5760,64) -> Half(129600,1:16,1440,16) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0666149 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0355465 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0685211 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0355465 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,2880,32) -> Half(129600,1:16,1440,16) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0690011 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.037632 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0690469 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.037632 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(129600,1:16,1440,16) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0877806 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0562286 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0878446 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0562286 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(129600,1:16,1440,16) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0639284 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512975 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.06192 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512975 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(129600,1:16,1440,16) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0719726 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.050749 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.073376 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.050749 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(129600,1:16,1440,16) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0792137 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.135899 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0789943 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0789943 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(129600,1:16,1440,16) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0874583 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0509074 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0867451 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0509074 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(129600,1:16,1440,16) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0656335 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0354523 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0655985 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0354523 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(129600,1:16,1440,16) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::ConvTranspose_644 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0656335 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.035605 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0658286 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.035605 +[03/18/2024-15:12:44] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) long-strided -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) long-strided -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:16,2880,16) -> Half(1036800,1:16,5760,32) *************** +[03/18/2024-15:12:44] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.981577 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.503515 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.04419 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.503515 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.868645 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.500443 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.14132 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.500443 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.371552 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.386926 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.660919 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.371552 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.484498 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.523703 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.561737 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.484498 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.989038 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.370688 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.989038 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.370688 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.26625 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.373029 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.388101 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.373029 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 5.07992 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.502345 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.95704 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.502345 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.616448 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.499419 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.666633 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.499419 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.38579 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.374199 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.56719 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.374199 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.59776 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.492837 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.7853 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.492837 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.476453 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.469431 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.476599 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.469431 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.477038 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.370103 +[03/18/2024-15:12:44] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.614546 +[03/18/2024-15:12:44] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.370103 +[03/18/2024-15:12:44] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:44] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.88009 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.498834 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.96903 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.498834 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.602112 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.649801 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.513609 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.513609 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.38945 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.471479 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.74815 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.471479 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.66681 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.387401 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.82505 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.387401 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.589239 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.370395 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.703488 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.370395 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.586021 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.370363 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.744741 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.370363 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.378587 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.390144 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.657714 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.378587 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.716937 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.376832 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.796233 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.376832 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.789358 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.377417 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.03307 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.377417 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.514779 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.384146 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.414281 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.384146 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.797431 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 1.11528 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.790821 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.790821 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.773577 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.263022 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.36352 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.263022 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.637806 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.51317 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.385166 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.385166 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.641024 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.377417 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.763611 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.377417 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.722944 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.377271 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.861184 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.377271 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.615863 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 1.54726 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.316416 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.316416 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.769902 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.331776 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.741669 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.331776 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.717531 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.320219 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.338798 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.320219 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.47342 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.405632 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.51771 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.405632 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.503808 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.374345 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.485376 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.374345 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.572855 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.457691 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.676864 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.457691 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 3.76408 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.85899 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 3.98541 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.85899 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.1453 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.371419 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.48223 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.371419 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.689006 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.250002 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.654336 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.250002 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.31353 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.410331 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.370981 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.370981 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.485102 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.505125 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.478354 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.478354 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.562176 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.37376 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.585143 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.37376 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.24346 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.837339 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.255854 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.255854 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.29334 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.379026 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.253952 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.253952 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.524293 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.353577 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.524288 +[03/18/2024-15:12:45] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.353577 +[03/18/2024-15:12:45] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:45] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.30197 +[03/18/2024-15:12:45] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.480256 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.0531 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.480256 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.596265 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.375346 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.634587 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.375346 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.672768 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.42613 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.605038 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.42613 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 3.85346 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.853138 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 3.92371 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.853138 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.49916 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.381074 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.34235 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.381074 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.527067 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.251611 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.527214 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.251611 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:16,5760,32) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.164 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.527067 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.385042 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.555442 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.385042 +[03/18/2024-15:12:46] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0770994 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.068224 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0771657 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.068224 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0785554 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0738583 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0787131 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0738583 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0510537 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.052029 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.074752 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0510537 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0647558 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0600747 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0502735 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0502735 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0724137 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0513097 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0693928 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0513097 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0693882 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0508099 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0514438 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0508099 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.259365 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0698758 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.247973 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0698758 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0670507 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0678278 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0668983 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0668983 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.218112 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0513813 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.213285 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0513813 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.227474 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0532343 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.227022 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0532343 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0599771 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0505036 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0598796 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0505036 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0596846 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0504686 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0595459 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0504686 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.251598 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0682179 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.245906 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0682179 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.066755 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0683093 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0665112 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0665112 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.213408 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0509562 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.213577 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0509562 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.228338 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0548571 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.229961 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0548571 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0702171 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0504686 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0704168 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0504686 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0700221 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0504686 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0700709 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0504686 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0496884 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0508099 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0660236 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0496884 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0710949 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0710598 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0737417 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0519802 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0732891 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0519802 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0559787 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.036352 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.041176 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.036352 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0648396 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.110885 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0650042 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0648396 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0648533 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0358434 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0451989 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0358434 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0598796 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0525653 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0496396 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0496396 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0693029 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0520411 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.068803 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0520411 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0762149 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0513036 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.076208 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0513036 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0555886 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.121344 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0372297 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0372297 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0690971 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0382903 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0689493 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0382903 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.068803 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.038328 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0421303 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.038328 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.246784 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0523703 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.247067 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0523703 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0647558 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0511421 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0647131 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0511421 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0757029 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.051005 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0757029 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.051005 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.22016 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.11336 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.214455 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.11336 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.227913 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0541745 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.228206 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0541745 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.069632 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0365349 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0696808 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0365349 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.246053 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0519314 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0493958 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0493958 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0638339 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0510095 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0640244 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0510095 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0744594 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0514438 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0745326 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0514438 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.213271 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.112709 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0350272 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0350272 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.227913 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0516008 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0348453 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0348453 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> onnx::Conv_651) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.066365 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0353682 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0670888 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0353682 +[03/18/2024-15:12:46] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0746057 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0674377 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0764343 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0674377 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0759223 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0681691 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0756297 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0681691 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0504823 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0492983 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0675352 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0492983 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0581303 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0556861 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.050016 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.050016 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.067779 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0505661 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0696442 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0505661 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.067779 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0505173 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0528549 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0505173 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.248832 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0695451 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.246345 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0695451 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0669989 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0676328 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0670476 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0669989 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.219867 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0515901 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.21387 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0515901 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.227621 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0554316 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.226743 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0554316 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.060963 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0532968 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0610011 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0532968 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0609067 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0507611 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0608594 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0507611 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.247369 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0685105 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.259218 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0685105 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0671451 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0682179 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0668526 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0668526 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.213728 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.051107 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.213138 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.051107 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.23435 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0527604 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.22923 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0527604 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0689493 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512975 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0690469 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512975 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0690469 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0513036 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0706606 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0513036 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0496884 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0500297 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.063616 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0496884 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0700221 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0510049 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0703147 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0510049 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0718994 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0518339 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0712899 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0518339 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0533943 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0371211 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0396754 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0371211 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.063488 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.10744 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0635855 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.063488 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0635855 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0358034 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0450834 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0358034 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0605623 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0528579 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0494933 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0494933 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0679665 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0541318 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0680716 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0541318 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0751909 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0519314 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0750446 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0519314 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0547596 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.12427 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0377051 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0377051 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0724731 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0400457 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0729234 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0400457 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0724846 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0402263 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0428206 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0402263 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.245029 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0521265 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.256146 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0521265 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0650971 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0523261 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0652922 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0523261 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0759954 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.051005 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0762149 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.051005 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.220014 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.107227 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.212558 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.107227 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.227913 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0534918 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.227657 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0534918 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0663055 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0366377 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0663162 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0366377 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.246638 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0516373 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0492983 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0492983 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0616351 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0507109 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0615375 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0507109 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.07168 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0514438 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.07168 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0514438 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.212407 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.107813 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0348745 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0348745 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.227621 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0511025 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0359074 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0359074 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(onnx::Conv_651 -> ) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0656838 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0347301 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0656823 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0347301 +[03/18/2024-15:12:46] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.874496 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.505856 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.870839 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.505856 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.05253 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.655945 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.0496 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.655945 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.371273 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.404187 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.808082 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.371273 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.504539 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.566272 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.381952 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.381952 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.03848 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.370834 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.02415 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.370834 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.21359 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.375808 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.394971 +[03/18/2024-15:12:46] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.375808 +[03/18/2024-15:12:46] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:46] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003e8 Time: 5.2439 +[03/18/2024-15:12:46] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.504978 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.93629 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.504978 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.597577 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.501321 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.509952 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.501321 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.54378 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.374345 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.47166 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.374345 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.69709 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.523557 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.84588 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.523557 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.485646 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.370075 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.594359 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.370075 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.576219 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.443246 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.593774 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.443246 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.99814 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.64 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.86195 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.64 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.513024 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.720457 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.513317 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.513024 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.57786 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.370834 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.56148 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.370834 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.61634 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.476453 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.53179 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.476453 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.583241 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.370981 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.646875 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.370981 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.657701 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.370981 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.756736 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.370981 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.488302 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.414866 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.648046 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.414866 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.817737 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.37771 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.863232 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.37771 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.814382 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.475575 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.837778 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.475575 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.496379 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.290391 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.330473 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.290391 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.873179 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 1.1096 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.850359 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.850359 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.774875 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.251173 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.363959 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.251173 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.542574 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.41355 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.521216 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.41355 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.624494 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.483182 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.62347 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.483182 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.694272 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.376978 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.916334 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.376978 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.612791 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 1.4965 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.31861 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.31861 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.642487 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.324023 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.642487 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.324023 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.639122 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.467529 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.338505 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.338505 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.49445 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.483621 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.46596 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.483621 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.492105 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.37493 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.490469 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.37493 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.576805 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.378587 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.576805 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.378587 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 3.95761 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.966949 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 3.87072 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.966949 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.3355 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.376686 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.30928 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.376686 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.644827 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.3672 +[03/18/2024-15:12:47] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.605915 +[03/18/2024-15:12:47] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.3672 +[03/18/2024-15:12:47] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:47] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.11092 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.404334 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.370981 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.370981 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.485083 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.467968 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.484937 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.467968 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.668233 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.374478 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.7168 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.374478 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 3.83984 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.843337 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.25717 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.25717 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 4.23307 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.380782 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.254121 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.254121 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.571685 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.341138 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.592311 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.341138 +[03/18/2024-15:12:48] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0755657 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0695832 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0784686 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0695832 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.079904 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0685592 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0805303 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0685592 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0510507 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0597333 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0505128 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0505128 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0604267 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0568076 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0605135 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0568076 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.069632 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512488 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0689493 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512488 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0669989 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0510568 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.067581 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0510568 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0660754 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0662187 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0659261 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0659261 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0739474 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0674743 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0746651 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0674743 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0756983 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0681204 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0753417 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0681204 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0503223 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0547535 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0502735 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0502735 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0574857 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0553935 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0575299 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0553935 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0673402 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0504686 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.067232 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0504686 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0671939 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0504686 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0676815 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0504686 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.564955 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0697356 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.564224 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0697356 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0730697 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0687543 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0679253 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0679253 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.516096 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0519314 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.519168 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0519314 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.552229 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0532907 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.648594 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0532907 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0608061 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0510415 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0596846 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0510415 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0591512 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0514438 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0589653 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0514438 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.614107 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0685501 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.639415 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0685501 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0657798 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0671314 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0656335 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0656335 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0664625 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0669501 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0667063 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0664625 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.519022 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512975 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.615863 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512975 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.62859 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0526141 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.610889 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0526141 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0572846 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0527436 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0574415 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0527436 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0573486 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.050371 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0571429 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.050371 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.567296 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.068803 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.56469 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.068803 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0664472 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0672472 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0718126 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0664472 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.560421 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0530042 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.517984 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0530042 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.601381 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0530149 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.548754 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0530149 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0678705 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0508648 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0681585 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0508648 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0684648 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0509638 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0685608 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0509638 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.564955 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0717531 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.566126 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0717531 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0669013 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0672351 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0668526 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0668526 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0720274 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0682667 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0701684 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0682667 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.516535 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0514469 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.589531 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0514469 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.61045 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0541745 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.55179 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0541745 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0690956 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0506149 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0689981 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0506149 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0690469 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0505585 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0690956 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0505585 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0510537 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0550034 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0495345 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0495345 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0682179 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512975 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0683642 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512975 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.069827 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.052029 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0699246 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.052029 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0529478 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0357291 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0527604 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0357291 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0633905 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.100997 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0631954 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0631954 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0650911 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.036096 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0658149 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.036096 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0491992 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.057539 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0510994 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0491992 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0709973 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0520731 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0707109 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0520731 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.072704 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512442 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.072704 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512442 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0357193 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0448023 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0371566 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0357193 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0557836 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.036352 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0558811 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.036352 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.064512 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.109568 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0644663 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0644663 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0644175 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0359463 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0644907 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0359463 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0594392 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0524678 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0621684 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0524678 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.070115 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0529554 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0698758 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0529554 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0784823 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0521265 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0784091 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0521265 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.057536 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.12939 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0588069 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.057536 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0744023 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0410697 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0745989 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0410697 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0744594 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0411474 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0437097 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0411474 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0648411 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.054467 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0500175 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0500175 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0711421 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0515901 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0711436 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0515901 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0799292 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.051395 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0803109 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.051395 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0587093 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.130633 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0381074 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0381074 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0351378 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0600762 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0369703 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0351378 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0735817 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0408137 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0735246 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0408137 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0736549 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0405943 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.044288 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0405943 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.519461 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0560168 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.583826 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0560168 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0681691 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0522728 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0680229 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0522728 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0795063 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0517379 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0754103 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0517379 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.498395 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.116009 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.466651 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.116009 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.554715 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0536792 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.49781 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0536792 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0692419 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0359531 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0690987 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0359531 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.581339 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0555032 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.520485 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0555032 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0628053 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0551269 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0629516 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0551269 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0731429 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512975 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.07168 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512975 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.462555 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.107593 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.468407 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.107593 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.503954 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0510568 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.500041 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0510568 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0653897 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0353719 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.06544 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0353719 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0653912 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0352549 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.064707 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0352549 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.519022 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0551497 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.613815 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0551497 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0606598 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0524587 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0607086 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0524587 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0701196 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0514377 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0701684 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0514377 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.519314 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.105545 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.465737 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.105545 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.503808 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0508587 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.034677 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.034677 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.063968 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0355511 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0644145 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0355511 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.51829 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0572952 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0498789 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0498789 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0601722 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0514926 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0599771 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0514926 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0686674 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0510049 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0686568 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0510049 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.466066 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.104155 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0344878 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0344878 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.501038 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0497874 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0347246 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0347246 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0638659 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0352046 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0638781 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0352046 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.184 -> ) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0638781 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0351104 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.063488 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0351104 +[03/18/2024-15:12:48] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> reg_0) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00479756 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0107252 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00422897 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00422897 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> reg_0) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00380812 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0182863 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00381606 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.00380812 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> reg_0) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00406489 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.020076 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00401257 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00401257 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> reg_0) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00369278 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0509074 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00280524 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00280524 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> reg_0) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.003632 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0509623 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00364537 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.003632 +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> reg_0) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00370227 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0529067 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00303848 +[03/18/2024-15:12:48] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00303848 +[03/18/2024-15:12:48] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:48] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:48] [V] [TRT] *************** Autotuning Reformat: Float(32400,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:48] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> height_0) (Reformat) +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00219283 +[03/18/2024-15:12:48] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.00364629 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00306004 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.00219283 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> height_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00225636 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0037474 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00225864 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.00225636 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> height_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00306422 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0179166 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00301714 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00301714 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> height_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00270715 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0451291 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00220891 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00220891 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> height_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00268572 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.045056 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00272423 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.00268572 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> height_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.002803 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0469943 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00268648 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00268648 +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(97200,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> dim_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00224643 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.00410802 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00433454 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.00224643 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(97200,1,540,3) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> dim_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0037819 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0153582 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00376602 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00376602 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> dim_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00411481 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0167919 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00411011 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00411011 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(64800,32400:2,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> dim_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00396219 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0459337 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00283877 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00283877 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> dim_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00390771 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0461166 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00390425 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00390425 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> dim_0) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.00400749 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0475429 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.00281367 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.00281367 +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(97200,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(97200,1,540,3) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(64800,32400:2,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(97200,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(97200,1,540,3) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(64800,32400:2,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(97200,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(97200,1,540,3) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(64800,32400:2,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(97200,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(97200,1,540,3) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(64800,32400:2,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(16588800,1,92160,512) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(16588800,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,1:4,23040,128) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(518400,1:4,2880,16) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(259200,1:8,1440,8) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(8294400,1,46080,256) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.331813 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.254537 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.420864 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.254537 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.324302 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.250587 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.407991 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.250587 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.189147 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189262 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.206409 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.189147 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.19456 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.209504 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.190757 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.190757 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.458606 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189733 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.385902 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189733 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.384878 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187831 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.194414 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187831 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.30181 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.257609 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.01642 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.257609 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.57126 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 4.17719 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 3.017 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 2.57126 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.01991 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187515 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.9908 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187515 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(4147200,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.13823 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.192219 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.11749 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.192219 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.239177 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187538 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.239177 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187538 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,1:8,5760,32) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.239323 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187685 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.239616 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187685 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.20178 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.252928 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.05458 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.252928 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(8294400,1,46080,256) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.382555 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.252489 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.355927 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.252489 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.08574 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189586 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.1169 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189586 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(4147200,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 2.03995 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.193536 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.99592 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.193536 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.276905 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.187392 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.28277 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.187392 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,1:8,5760,32) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.283063 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189147 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.348306 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189147 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.187977 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189733 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.261266 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.187977 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,1,46080,256) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.345527 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.193714 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.344795 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.193714 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.484937 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190459 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.453152 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190459 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.218697 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.133413 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.154624 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.133413 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.331643 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.50805 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.342016 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.331643 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.345819 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.128219 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.17408 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.128219 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.347282 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.195881 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.190903 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.190903 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(8294400,1,46080,256) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.357961 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190345 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.283502 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190345 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.381367 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.194706 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.312027 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.194706 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.223086 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.558519 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.146578 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.146578 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.297106 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.151991 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.296814 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.151991 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,1:8,5760,32) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.296814 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.15184 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.164133 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.15184 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.29685 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.191049 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.16824 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.191049 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(8294400,1,46080,256) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.263159 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.189733 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.396581 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.189733 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.31115 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.204654 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.309394 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.204654 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.02532 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.543451 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.955246 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.543451 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(4147200,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.01361 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.204763 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.14059 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.204763 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,1:8,5760,32) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.391753 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.131291 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.354619 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.131291 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.16386 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.193102 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.18827 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.18827 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(8294400,1,46080,256) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.265947 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.190171 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.265947 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.190171 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.408425 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.191927 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.380928 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.191927 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(8294400,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.955392 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.446487 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.131218 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.131218 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(4147200,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 1.14264 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.205824 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.129829 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.129829 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat( -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.330313 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.129463 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.353865 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.129463 +[03/18/2024-15:12:49] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0774583 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0689493 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0770354 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0689493 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0771589 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0678811 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0787749 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0678811 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.050723 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0584655 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0505173 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0505173 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0610499 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0558324 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0577463 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0558324 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.067779 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0513463 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0671467 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0513463 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.067389 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0508587 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0674377 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0508587 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0681295 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0664747 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0658834 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0658834 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0744594 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0675398 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0744571 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0675398 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0757029 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0673402 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0759131 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0673402 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0507124 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0578804 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0513448 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0507124 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0602209 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0570895 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0603185 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0570895 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0703147 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0511436 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0699733 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0511436 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0691383 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0507124 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0689493 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0507124 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.530871 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.069632 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.578706 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.069632 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0680716 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0675352 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0690849 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0675352 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.479671 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0518339 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.475008 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0518339 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.591579 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0569051 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.509367 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0569051 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0637318 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0511025 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0637257 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0511025 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0634392 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0642682 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.524869 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0694857 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.587922 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0694857 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0662674 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0672427 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0663131 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0662674 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0672457 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0735977 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0677181 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0672457 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.562615 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0517851 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.473819 +[03/18/2024-15:12:49] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0517851 +[03/18/2024-15:12:49] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:49] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.511671 +[03/18/2024-15:12:49] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0540373 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.510245 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0540373 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0620632 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0516373 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0621714 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0516373 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0621227 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0505219 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0622491 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0505219 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.524873 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0735817 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.604891 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0735817 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0680716 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0670476 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0670583 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0670476 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.531177 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0518263 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.472795 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0518263 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.62069 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0537356 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.589531 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0537356 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0683642 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0507124 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0683764 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0507124 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0685105 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0511558 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0680229 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0511558 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.522679 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0684617 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.526629 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0684617 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0666636 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0676815 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0666149 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0666149 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0687543 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0669989 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0687208 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0669989 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.474551 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0513874 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.534235 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0513874 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.509221 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0547977 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.508622 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0547977 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0709486 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0505173 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0711436 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0505173 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0710949 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0516876 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0699733 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0516876 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0496884 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0555886 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0492008 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0492008 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0687055 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0513966 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0690956 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0513966 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.070173 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.051395 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0702171 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.051395 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0533943 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.035912 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0533943 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.035912 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.063488 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.102967 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0663162 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.063488 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0648533 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0362057 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0647558 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0362057 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0493471 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.057149 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0500297 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0493471 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0703634 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.051395 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0702171 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.051395 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0723291 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0523825 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0725577 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0523825 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0340517 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0444343 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0369737 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0340517 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0552 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0360229 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0533455 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0360229 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0633905 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.106578 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0633859 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0633859 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0634392 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0367177 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0631467 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0367177 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0580754 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0522286 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0591528 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0522286 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0698758 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0524648 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0695863 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0524648 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0781166 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0516389 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0779703 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0516389 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0575299 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.126683 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0562225 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0562225 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0708023 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0393189 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0706651 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0393189 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0707535 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0400789 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0426366 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0400789 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0619764 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0529067 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0498347 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0498347 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0684648 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.051395 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0684617 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.051395 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0759406 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.052227 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0759223 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.052227 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0556419 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.120247 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0362057 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0362057 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0344923 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0553935 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0371566 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003e8 Time: 0.0344923 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.068413 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0381063 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0683642 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0381063 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0679771 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0378514 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0421429 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0378514 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.272969 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0521265 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.338537 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0521265 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0616838 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512488 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0616655 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512488 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0718263 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0519802 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0716069 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0519802 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.244882 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.107227 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.239909 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.107227 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.253536 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0511512 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.255561 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0511512 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0659749 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0353207 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0659749 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0353207 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.272238 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0516267 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.272677 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0516267 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0611825 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.051485 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0611871 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.051485 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0712411 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0510141 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0713387 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0510141 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.240055 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.106569 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.240201 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.106569 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.254976 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0504198 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.254391 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0504198 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0653928 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0359863 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0654324 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0359863 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0654248 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0351881 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.065213 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0351881 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.347013 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0521265 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.334112 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0521265 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0606568 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512472 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0606126 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512472 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0704122 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.054653 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0707535 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.054653 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.238592 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.107161 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.238885 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.107161 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.254245 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0505585 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.034443 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.034443 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0650971 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0354304 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0650971 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0354304 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.271799 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0515901 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0537356 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0515901 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.060509 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0512488 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0601234 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0512488 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.069632 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0507611 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0695832 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0507611 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.240069 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.105266 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0354359 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0354359 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.253074 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0489569 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0342309 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.0342309 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0635246 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0348453 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.0640305 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0348453 +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Optimizer Reformat(input.568 -> ) (Reformat) +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003e8 Time: 0.0633463 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x00000000000003ea Time: 0.0350245 +[03/18/2024-15:12:50] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.06256 +[03/18/2024-15:12:50] [V] [TRT] Fastest Tactic: 0x00000000000003ea Time: 0.0350245 +[03/18/2024-15:12:50] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(97200,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(97200,1,540,3) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(64800,32400:2,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(8294400,1,46080,256) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(2073600,1:4,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(8294400,32400,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(4147200,32400:2,180,1) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,1:8,5760,32) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(2073600,1:4,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(8294400,1,46080,256) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(8294400,32400,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(4147200,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,1:4,11520,64) long-strided *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(1036800,1:8,5760,32) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:12:50] [V] [TRT] =============== Computing reformatting costs: +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(64800,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(64800,1,360,2) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Float(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,32400:2,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:4,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning Reformat: Half(32400,1:8,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] =============== Computing costs for +[03/18/2024-15:12:50] [V] [TRT] *************** Autotuning format combination: Float(8294400,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CudaDepthwiseConvolution) +[03/18/2024-15:12:50] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:50] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (FusedConvActConvolution) +[03/18/2024-15:12:50] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:51] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CudnnConvolution) +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x0000000000000000 Time: 4.16037 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x0000000000000001 Time: 3.33063 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x0000000000000002 Time: 5.63595 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x0000000000000005 Time: 22.5346 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x0000000000000006 Time: 2.34891 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x0000000000000038 Time: 5.1968 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x0000000000000039 Time: 3.01583 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x000000000000003a Time: 5.86765 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x000000000000003d Time: 22.5445 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x000000000000003e Time: 2.7209 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x0000000000000070 Time: 5.11766 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x0000000000000071 Time: 4.81075 +[03/18/2024-15:12:51] [V] [TRT] Tactic: 0x0000000000000072 Time: 7.17619 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x0000000000000075 Time: 22.8302 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x0000000000000076 Time: 2.45336 +[03/18/2024-15:12:52] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 2.34891 +[03/18/2024-15:12:52] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskGemmConvolution) +[03/18/2024-15:12:52] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:52] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskFlattenConvolution) +[03/18/2024-15:12:52] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:52] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskConvolution) +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 3.15012 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 3.24198 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 4.23278 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 2.29917 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 3.18245 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 3.80284 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 8.10408 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 11.4177 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 3.48131 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 5.76746 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 3.85843 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 7.09913 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 5.72824 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x4727434768e46395 Time: 4.4345 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 3.8697 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 3.46463 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 5.9253 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 4.06543 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 4.22546 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:12:52] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 3.71495 +[03/18/2024-15:12:52] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 7.53825 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 3.60009 +[03/18/2024-15:12:53] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 2.29917 +[03/18/2024-15:12:53] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:12:53] [V] [TRT] *************** Autotuning format combination: Float(8294400,1,46080,256) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:53] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskFlattenConvolution) +[03/18/2024-15:12:53] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:53] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskConvolution) +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x27b316f52c109002 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x27b316f52c109002 Time: 3.18496 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x128_relu_exp_medium_nhwc_tn_v1 Tactic: 0xd9031472c05adf51 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0xd9031472c05adf51 Time: 3.45527 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x3e2b881168d9689d +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x3e2b881168d9689d Time: 4.24082 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0xf90060ce8193b811 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0xf90060ce8193b811 Time: 3.50866 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0xbdfdef6b84f7ccc9 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0xbdfdef6b84f7ccc9 Time: 3.54465 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x412c44dfeaf9161d +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x412c44dfeaf9161d Time: 3.81952 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x7bc32c782b800c48 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x7bc32c782b800c48 Time: 3.50749 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 6.35831 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 4.41359 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 5.33051 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 3.37481 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x3e191488237fab8f +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x3e191488237fab8f Time: 4.34937 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 6.96496 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 7.15322 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 6.14927 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 7.65264 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 4.00706 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 3.60068 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x128_relu_exp_large_nhwc_tn_v1 Tactic: 0xca7eeb8d9143d738 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0xca7eeb8d9143d738 Time: 3.6314 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 4.33576 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 3.3912 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x128_relu_exp_small_nhwc_tn_v1 Tactic: 0x5030121339a48bf3 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x5030121339a48bf3 Time: 3.69035 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 6.92882 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:12:53] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 3.44942 +[03/18/2024-15:12:53] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 6.63771 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0x634e99502974e4da +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x634e99502974e4da Time: 3.74125 +[03/18/2024-15:12:54] [V] [TRT] Fastest Tactic: 0x27b316f52c109002 Time: 3.18496 +[03/18/2024-15:12:54] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x27b316f52c109002 +[03/18/2024-15:12:54] [V] [TRT] *************** Autotuning format combination: Float(2073600,1:4,11520,64) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CudaDepthwiseConvolution) +[03/18/2024-15:12:54] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskGemmConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskFlattenConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskConvolution) +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 2.09159 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 2.2528 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 2.07184 +[03/18/2024-15:12:54] [V] [TRT] Fastest Tactic: 0xb443c221fcb1565b Time: 2.07184 +[03/18/2024-15:12:54] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xb443c221fcb1565b +[03/18/2024-15:12:54] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CudnnConvolution) +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x0000000000000000 Time: 3.76422 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x0000000000000001 Time: 4.09761 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x0000000000000002 Time: 5.32568 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x0000000000000005 Time: 22.3544 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x0000000000000006 Time: 2.59657 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x0000000000000038 Time: 4.66359 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x000000000000003a Time: 5.1633 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x000000000000003d Time: 22.1547 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x000000000000003e Time: 2.90216 +[03/18/2024-15:12:54] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 2.59657 +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskGemmConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskFlattenConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000006 +[03/18/2024-15:12:54] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400:2,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (FusedConvActConvolution) +[03/18/2024-15:12:54] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskFlattenConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:4,11520,64) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskFlattenConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:8,5760,32) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskFlattenConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:8,5760,32) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CudaDepthwiseConvolution) +[03/18/2024-15:12:54] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskGemmConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskFlattenConvolution) +[03/18/2024-15:12:54] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:54] [V] [TRT] --------------- Timing Runner: Conv_15 + Relu_16 (CaskConvolution) +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.62069 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.504101 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.56437 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.539648 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.525605 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.647314 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.625371 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.530139 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.772974 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.681106 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.622299 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.622299 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.556325 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.498103 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.692809 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.484352 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.582363 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.492983 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.590702 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.532919 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.761417 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.558519 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.679205 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.566126 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.638537 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.696466 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.554569 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.600064 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.722359 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.654336 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.670866 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.601527 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:12:54] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.637806 +[03/18/2024-15:12:54] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.63488 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.727479 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.691639 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.691054 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.810569 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.638098 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.624055 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.809545 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.741074 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.676864 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.551936 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.831049 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.51829 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.935205 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.634455 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.578432 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.47221 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.566857 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.641902 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.513463 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.760393 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.657993 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.497225 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 1.18243 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.653637 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.640585 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.531602 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.63808 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.528823 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.521509 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.514633 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.827255 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.984503 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.564955 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 1.0458 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.537015 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.569198 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.674231 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.830171 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.911689 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.978798 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.516242 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.511854 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.631954 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.721042 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.53248 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.673499 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.887808 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.545499 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.6912 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.615424 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.703488 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.537307 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.544622 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.747538 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.741376 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.613509 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 1.0338 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.542427 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.660041 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.593481 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.637659 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.589371 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.736841 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 1.22836 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.58763 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.805742 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 1.13695 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.610889 +[03/18/2024-15:12:55] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.531168 +[03/18/2024-15:12:55] [V] [TRT] Fastest Tactic: 0x263a38afd75e3a43 Time: 0.47221 +[03/18/2024-15:12:55] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:12:55] [V] [TRT] =============== Computing costs for +[03/18/2024-15:12:55] [V] [TRT] *************** Autotuning format combination: Float(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:55] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CudaDepthwiseConvolution) +[03/18/2024-15:12:55] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:55] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (FusedConvActConvolution) +[03/18/2024-15:12:55] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:55] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CudnnConvolution) +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.21901 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0000000000000001 Time: 1.57857 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0000000000000002 Time: 2.99328 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0000000000000005 Time: 11.5655 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0000000000000006 Time: 1.44879 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0000000000000038 Time: 2.29273 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0000000000000039 Time: 1.74724 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x000000000000003a Time: 2.91562 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x000000000000003d Time: 11.6982 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x000000000000003e Time: 1.58149 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0000000000000070 Time: 2.55327 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0000000000000071 Time: 2.37787 +[03/18/2024-15:12:55] [V] [TRT] Tactic: 0x0000000000000072 Time: 3.34 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x0000000000000075 Time: 11.8487 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x0000000000000076 Time: 1.74475 +[03/18/2024-15:12:56] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 1.44879 +[03/18/2024-15:12:56] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskGemmConvolution) +[03/18/2024-15:12:56] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:56] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskFlattenConvolution) +[03/18/2024-15:12:56] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:56] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskConvolution) +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 2.28308 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 1.77445 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 1.83706 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 1.27093 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 1.91766 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 1.92102 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 4.01057 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 5.78341 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 1.87803 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 2.68902 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 2.04742 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 3.01188 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 2.98057 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x4727434768e46395 Time: 2.15333 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 1.85871 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 1.90976 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 2.77051 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 2.04712 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 2.176 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 1.99139 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 3.79231 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 1.77342 +[03/18/2024-15:12:56] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 1.27093 +[03/18/2024-15:12:56] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:12:56] [V] [TRT] *************** Autotuning format combination: Float(4147200,1,23040,128) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:56] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskFlattenConvolution) +[03/18/2024-15:12:56] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:56] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskConvolution) +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x27b316f52c109002 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x27b316f52c109002 Time: 1.60212 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x128_relu_exp_medium_nhwc_tn_v1 Tactic: 0xd9031472c05adf51 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xd9031472c05adf51 Time: 1.61042 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x3e2b881168d9689d +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x3e2b881168d9689d Time: 2.05707 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0xf90060ce8193b811 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xf90060ce8193b811 Time: 1.73919 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0xbdfdef6b84f7ccc9 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xbdfdef6b84f7ccc9 Time: 1.75748 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x412c44dfeaf9161d +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x412c44dfeaf9161d Time: 1.81817 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x7bc32c782b800c48 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x7bc32c782b800c48 Time: 1.74374 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 2.96975 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 1.91181 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 2.60623 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 1.4671 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x3e191488237fab8f +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x3e191488237fab8f Time: 2.06497 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 3.29494 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 3.53966 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 3.60243 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 3.74404 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 2.04815 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 1.88753 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x128_relu_exp_large_nhwc_tn_v1 Tactic: 0xca7eeb8d9143d738 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xca7eeb8d9143d738 Time: 1.78864 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 2.0088 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 1.63152 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x128_relu_exp_small_nhwc_tn_v1 Tactic: 0x5030121339a48bf3 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x5030121339a48bf3 Time: 1.97193 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 3.13915 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:12:56] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 1.74665 +[03/18/2024-15:12:56] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 3.48321 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0x634e99502974e4da +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x634e99502974e4da Time: 1.84042 +[03/18/2024-15:12:57] [V] [TRT] Fastest Tactic: 0x1da91d865428f237 Time: 1.4671 +[03/18/2024-15:12:57] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x1da91d865428f237 +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CudaDepthwiseConvolution) +[03/18/2024-15:12:57] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskGemmConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 1.41195 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 1.31277 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.993573 +[03/18/2024-15:12:57] [V] [TRT] Fastest Tactic: 0xb443c221fcb1565b Time: 0.993573 +[03/18/2024-15:12:57] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xb443c221fcb1565b +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CudnnConvolution) +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.00997 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000001 Time: 1.81745 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000002 Time: 2.46637 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000005 Time: 11.6088 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000006 Time: 1.64381 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000038 Time: 2.32214 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x000000000000003a Time: 2.72296 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x000000000000003d Time: 11.4727 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x000000000000003e Time: 1.8846 +[03/18/2024-15:12:57] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 1.64381 +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskGemmConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000006 +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400:2,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (FusedConvActConvolution) +[03/18/2024-15:12:57] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CudaDepthwiseConvolution) +[03/18/2024-15:12:57] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskGemmConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_17 + Relu_18 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.547401 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.338505 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.281161 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.287744 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.246638 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.367762 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.30091 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.266683 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.311589 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.459474 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.318025 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.301349 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.294327 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.285669 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.400366 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.28848 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.304274 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.301349 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.366592 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.377271 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.365275 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.282917 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.303689 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.356791 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.348014 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.351525 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.300471 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.280549 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.362203 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.313083 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.307931 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.298715 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.302226 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.361307 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.359717 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.291255 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.380928 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.346249 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.346258 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.290939 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.324901 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.44661 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.307639 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.29184 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.463433 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.425678 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.485266 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.290523 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.298094 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.354743 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.269897 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.270336 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.263739 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.347721 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.337042 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.248539 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.560576 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.289646 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.410185 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.263314 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.288183 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.294181 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.294619 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.358267 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.376686 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.363813 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.351854 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.450587 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.271328 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.289353 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.280987 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.386926 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.485522 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.502935 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.273701 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.263899 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.380197 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.367899 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.271653 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.300005 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.491227 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.290377 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.30789 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.315552 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.301934 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.324315 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.297106 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.29301 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.411502 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.424229 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.512731 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.286574 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.280416 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.394971 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.277504 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.271945 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.370542 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.759223 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.351525 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.331191 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.526775 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.40331 +[03/18/2024-15:12:57] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.283063 +[03/18/2024-15:12:57] [V] [TRT] Fastest Tactic: 0xa927df92ac1ef1b8 Time: 0.246638 +[03/18/2024-15:12:57] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:12:57] [V] [TRT] =============== Computing costs for +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(4147200,1,23040,128) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400:2,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_19 + Relu_20 (FusedConvActConvolution) +[03/18/2024-15:12:57] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_19 + Relu_20 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_19 + Relu_20 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_19 + Relu_20 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_19 + Relu_20 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_19 + Relu_20 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_19 + Relu_20 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:57] [V] [TRT] =============== Computing costs for +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(4147200,1,23040,128) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400:2,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_21 + Relu_22 (FusedConvActConvolution) +[03/18/2024-15:12:57] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_21 + Relu_22 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_21 + Relu_22 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_21 + Relu_22 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_21 + Relu_22 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_21 + Relu_22 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_21 + Relu_22 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:57] [V] [TRT] =============== Computing costs for +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(4147200,1,23040,128) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400:2,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_23 + Relu_24 (FusedConvActConvolution) +[03/18/2024-15:12:57] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_23 + Relu_24 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_23 + Relu_24 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_23 + Relu_24 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_23 + Relu_24 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_23 + Relu_24 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_23 + Relu_24 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:57] [V] [TRT] =============== Computing costs for +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(4147200,32400,180,1) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(4147200,1,23040,128) -> Float(4147200,1,23040,128) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(1036800,1:4,5760,32) -> Float(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400,180,1) -> Half(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400:2,180,1) -> Half(2073600,32400:2,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_25 + Relu_26 (FusedConvActConvolution) +[03/18/2024-15:12:57] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_25 + Relu_26 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_25 + Relu_26 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:4,5760,32) -> Half(1036800,1:4,5760,32) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_25 + Relu_26 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_25 + Relu_26 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Float(4147200,32400,180,1) *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_25 + Relu_26 (CaskFlattenConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_25 + Relu_26 (CaskConvolution) +[03/18/2024-15:12:57] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Half(518400,1:8,2880,16) *************** +[03/18/2024-15:12:57] [V] [TRT] =============== Computing costs for +[03/18/2024-15:12:57] [V] [TRT] *************** Autotuning format combination: Float(4147200,32400,180,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CudaDepthwiseConvolution) +[03/18/2024-15:12:57] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (FusedConvActConvolution) +[03/18/2024-15:12:57] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:57] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CudnnConvolution) +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.24694 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.895561 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000002 Time: 1.13474 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000005 Time: 1.77518 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000038 Time: 1.27941 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000039 Time: 0.980553 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x000000000000003a Time: 1.34788 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x000000000000003d Time: 1.79215 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000070 Time: 1.48144 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000071 Time: 0.906094 +[03/18/2024-15:12:57] [V] [TRT] Tactic: 0x0000000000000072 Time: 1.16283 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000075 Time: 1.77825 +[03/18/2024-15:12:58] [V] [TRT] Fastest Tactic: 0x0000000000000001 Time: 0.895561 +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:58] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskGemmConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 0.466651 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_interior_nn_v1 Tactic: 0xa8ef60e712f8ad24 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa8ef60e712f8ad24 Time: 0.360302 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.390418 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.465481 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x32_relu_interior_nn_v1 Tactic: 0x9808072e706def96 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x9808072e706def96 Time: 0.419109 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_relu_interior_nn_v1 Tactic: 0xc3cf6e1d1c6aff27 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xc3cf6e1d1c6aff27 Time: 0.350377 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nchwkrsc_nchw_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r1s1_aligna4_alignc4 Tactic: 0x7f0145cb49517338 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x7f0145cb49517338 Time: 0.521509 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 0.89088 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 1.40244 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 0.69749 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0xe5603263b7f00303 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xe5603263b7f00303 Time: 0.607232 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.516096 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 0.809838 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 0.693541 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 0.410331 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 0.515365 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0xc0b05b61d128e46e +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xc0b05b61d128e46e Time: 0.512731 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.444709 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0x2ee10e11d6651675 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x2ee10e11d6651675 Time: 0.740937 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 0.548571 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0x865894c4635db7fd +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x865894c4635db7fd Time: 0.538921 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 1.06452 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.635319 +[03/18/2024-15:12:58] [V] [TRT] Fastest Tactic: 0xc3cf6e1d1c6aff27 Time: 0.350377 +[03/18/2024-15:12:58] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc3cf6e1d1c6aff27 +[03/18/2024-15:12:58] [V] [TRT] *************** Autotuning format combination: Float(4147200,32400,180,1) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CudaDepthwiseConvolution) +[03/18/2024-15:12:58] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (FusedConvActConvolution) +[03/18/2024-15:12:58] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CudnnConvolution) +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.14556 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000001 Time: 1.09627 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000002 Time: 1.23743 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000005 Time: 1.6779 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000038 Time: 1.16063 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000039 Time: 1.09173 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x000000000000003a Time: 1.30428 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x000000000000003d Time: 1.68363 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000070 Time: 1.14747 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000071 Time: 1.06745 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000072 Time: 1.23259 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000075 Time: 1.72412 +[03/18/2024-15:12:58] [V] [TRT] Fastest Tactic: 0x0000000000000071 Time: 1.06745 +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:58] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskGemmConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 0.474258 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_interior_nn_v1 Tactic: 0xa8ef60e712f8ad24 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa8ef60e712f8ad24 Time: 0.462409 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.59787 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.385755 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x32_relu_interior_nn_v1 Tactic: 0x9808072e706def96 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x9808072e706def96 Time: 0.438272 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_relu_interior_nn_v1 Tactic: 0xc3cf6e1d1c6aff27 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xc3cf6e1d1c6aff27 Time: 0.372297 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nchwkrsc_nchw_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r1s1_aligna4_alignc4 Tactic: 0x7f0145cb49517338 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x7f0145cb49517338 Time: 0.438002 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nchwkrsc_nchw_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_simple_t1r1s1_aligna4_alignc4 Tactic: 0xa419b3b68f2da07b +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa419b3b68f2da07b Time: 0.416896 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 1.15302 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 1.23816 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0x1fc87d7eb370bb7a +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x1fc87d7eb370bb7a Time: 0.605769 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 0.678181 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0xe5603263b7f00303 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xe5603263b7f00303 Time: 0.608983 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.519022 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0x9de226a0c44627c4 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x9de226a0c44627c4 Time: 0.478793 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0x90f8f2915f87ed77 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x90f8f2915f87ed77 Time: 0.688421 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 0.8192 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0x8e3884f0eaec3ecd +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x8e3884f0eaec3ecd Time: 0.547579 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 0.837925 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 0.422181 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0x828d0ea88c66fce7 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x828d0ea88c66fce7 Time: 0.789065 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 0.538331 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0xc0b05b61d128e46e +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xc0b05b61d128e46e Time: 0.535406 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.457435 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0x2ee10e11d6651675 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x2ee10e11d6651675 Time: 0.579291 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 0.553984 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0x9cd5cdc35441c505 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x9cd5cdc35441c505 Time: 0.673207 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0x865894c4635db7fd +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x865894c4635db7fd Time: 0.523995 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0xfff46c7893896eb1 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xfff46c7893896eb1 Time: 0.491081 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 1.0458 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.625934 +[03/18/2024-15:12:58] [V] [TRT] Fastest Tactic: 0xc3cf6e1d1c6aff27 Time: 0.372297 +[03/18/2024-15:12:58] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc3cf6e1d1c6aff27 +[03/18/2024-15:12:58] [V] [TRT] *************** Autotuning format combination: Float(4147200,1,23040,128) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:58] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x27b316f52c109002 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x27b316f52c109002 Time: 0.434176 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_exp_medium_nhwc_tn_v1 Tactic: 0xd9031472c05adf51 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xd9031472c05adf51 Time: 0.380489 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x3e2b881168d9689d +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x3e2b881168d9689d Time: 0.783799 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_exp_interior_nhwc_tn_v1 Tactic: 0x17173deba0b64484 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x17173deba0b64484 Time: 0.380197 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_interior_nhwc_tn_v1 Tactic: 0xae0c89d047932ba3 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xae0c89d047932ba3 Time: 0.359863 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0xf90060ce8193b811 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xf90060ce8193b811 Time: 0.441198 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_interior_nhwc_tn_v1 Tactic: 0xe47307053a42b3e4 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xe47307053a42b3e4 Time: 0.46197 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x412c44dfeaf9161d +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x412c44dfeaf9161d Time: 0.416654 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x7bc32c782b800c48 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x7bc32c782b800c48 Time: 0.377678 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_interior_nhwc_tn_v1 Tactic: 0xc7feb33970feefa7 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xc7feb33970feefa7 Time: 0.658757 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 0.678034 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0x35f26f9c09557d86 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x35f26f9c09557d86 Time: 0.423611 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 0.714898 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.454363 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0x55d80c17b1cd982d +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x55d80c17b1cd982d Time: 0.469723 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x3e191488237fab8f +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x3e191488237fab8f Time: 0.72821 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 0.816128 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0x1022069e6f8d9aeb +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x1022069e6f8d9aeb Time: 0.442368 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 0.965778 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.484498 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.640878 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 0.536576 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_exp_small_nhwc_tn_v1 Tactic: 0x5030121339a48bf3 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x5030121339a48bf3 Time: 0.430226 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 0.883858 +[03/18/2024-15:12:58] [V] [TRT] Fastest Tactic: 0xae0c89d047932ba3 Time: 0.359863 +[03/18/2024-15:12:58] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xae0c89d047932ba3 +[03/18/2024-15:12:58] [V] [TRT] *************** Autotuning format combination: Float(4147200,1,23040,128) -> Float(8294400,1,46080,256) *************** +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:58] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x27b316f52c109002 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x27b316f52c109002 Time: 0.456997 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_exp_medium_nhwc_tn_v1 Tactic: 0xd9031472c05adf51 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xd9031472c05adf51 Time: 0.423351 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x3e2b881168d9689d +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x3e2b881168d9689d Time: 0.565979 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_exp_interior_nhwc_tn_v1 Tactic: 0x17173deba0b64484 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x17173deba0b64484 Time: 0.492247 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_interior_nhwc_tn_v1 Tactic: 0xae0c89d047932ba3 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xae0c89d047932ba3 Time: 0.402578 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0xf90060ce8193b811 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xf90060ce8193b811 Time: 0.393216 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_interior_nhwc_tn_v1 Tactic: 0xe47307053a42b3e4 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xe47307053a42b3e4 Time: 0.390437 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x412c44dfeaf9161d +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x412c44dfeaf9161d Time: 0.441051 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x7bc32c782b800c48 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x7bc32c782b800c48 Time: 0.412818 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_interior_nhwc_tn_v1 Tactic: 0xc7feb33970feefa7 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xc7feb33970feefa7 Time: 0.611621 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 0.899072 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0xc7b3afceb5fb03c0 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xc7b3afceb5fb03c0 Time: 0.484352 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0x35f26f9c09557d86 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x35f26f9c09557d86 Time: 0.844361 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 0.805888 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.641902 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0x55d80c17b1cd982d +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x55d80c17b1cd982d Time: 0.631077 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x3e191488237fab8f +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x3e191488237fab8f Time: 0.668526 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0xd55ee6fd0b56f808 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xd55ee6fd0b56f808 Time: 0.475867 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 1.03658 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0x90898977fc8ce537 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x90898977fc8ce537 Time: 0.515365 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0xbc0bba0ff1a92939 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xbc0bba0ff1a92939 Time: 0.639269 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r1s1_aligna4_alignc4 Tactic: 0x1022069e6f8d9aeb +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x1022069e6f8d9aeb Time: 0.459483 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0xd9eb6ca56ddc3a22 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xd9eb6ca56ddc3a22 Time: 0.648631 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 1.09027 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.483182 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.704073 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_simple_t1r1s1_aligna4_alignc4 Tactic: 0x1fb90698107bb33a +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x1fb90698107bb33a Time: 0.730258 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 0.530139 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_scudnn_128x128_relu_exp_small_nhwc_tn_v1 Tactic: 0x5030121339a48bf3 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x5030121339a48bf3 Time: 0.541257 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 0.758199 +[03/18/2024-15:12:58] [V] [TRT] Fastest Tactic: 0xe47307053a42b3e4 Time: 0.390437 +[03/18/2024-15:12:58] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xe47307053a42b3e4 +[03/18/2024-15:12:58] [V] [TRT] *************** Autotuning format combination: Float(1036800,1:4,5760,32) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CudaDepthwiseConvolution) +[03/18/2024-15:12:58] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:58] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskGemmConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.358985 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r1s1 Tactic: 0x130df49cb195156b +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x130df49cb195156b Time: 0.351054 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.35355 +[03/18/2024-15:12:58] [V] [TRT] Fastest Tactic: 0x130df49cb195156b Time: 0.351054 +[03/18/2024-15:12:58] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x130df49cb195156b +[03/18/2024-15:12:58] [V] [TRT] *************** Autotuning format combination: Float(1036800,1:4,5760,32) -> Float(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CudaDepthwiseConvolution) +[03/18/2024-15:12:58] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:58] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskGemmConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.325925 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_simple_t1r1s1 Tactic: 0x9dece0dc37e90462 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x9dece0dc37e90462 Time: 0.316128 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r1s1 Tactic: 0x130df49cb195156b +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x130df49cb195156b Time: 0.381513 +[03/18/2024-15:12:58] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.32139 +[03/18/2024-15:12:58] [V] [TRT] Fastest Tactic: 0x9dece0dc37e90462 Time: 0.316128 +[03/18/2024-15:12:58] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x9dece0dc37e90462 +[03/18/2024-15:12:58] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CudnnConvolution) +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.929207 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.58485 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.764635 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000005 Time: 1.43784 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000038 Time: 1.13353 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x000000000000003a Time: 0.913115 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x000000000000003d Time: 1.59876 +[03/18/2024-15:12:58] [V] [TRT] Fastest Tactic: 0x0000000000000001 Time: 0.58485 +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:58] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskGemmConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:58] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:58] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000001 +[03/18/2024-15:12:58] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400,180,1) -> Half(8294400,32400,180,1) *************** +[03/18/2024-15:12:58] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CudnnConvolution) +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.920722 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.777833 +[03/18/2024-15:12:58] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.856649 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x0000000000000005 Time: 1.53585 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.892197 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x000000000000003a Time: 0.904485 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x000000000000003d Time: 1.59568 +[03/18/2024-15:12:59] [V] [TRT] Fastest Tactic: 0x0000000000000001 Time: 0.777833 +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskGemmConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000001 +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400:2,180,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400:2,180,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (FusedConvActConvolution) +[03/18/2024-15:12:59] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400:2,180,1) -> Half(8294400,32400,180,1) *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400:2,180,1) -> Half(4147200,32400:2,180,1) *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (FusedConvActConvolution) +[03/18/2024-15:12:59] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:4,5760,32) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:4,5760,32) -> Half(2073600,1:4,11520,64) *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CudaDepthwiseConvolution) +[03/18/2024-15:12:59] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskGemmConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.393655 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.15621 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.149504 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.173202 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_interior_nhwc_tn_v1 Tactic: 0xeec2cfc9249c3239 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xeec2cfc9249c3239 Time: 0.172891 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.130098 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0x483db0113d970335 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x483db0113d970335 Time: 0.143506 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0x8d15f485c8c7f871 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x8d15f485c8c7f871 Time: 0.14197 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.161673 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_interior_nhwc_tn_v1 Tactic: 0xfb66471e53543444 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xfb66471e53543444 Time: 0.16384 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.175689 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.154917 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0x3f725d7f77411cdc +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3f725d7f77411cdc Time: 0.128658 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_interior_nhwc_tn_v1 Tactic: 0xc0df55afc74af7ab +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc0df55afc74af7ab Time: 0.268873 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_interior_nhwc_tn_v1 Tactic: 0x1f114e67977d5401 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x1f114e67977d5401 Time: 0.191634 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.173495 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0xc9d48aa637bf7810 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc9d48aa637bf7810 Time: 0.153307 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.145262 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.197778 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.260827 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_interior_nhwc_tn_v1 Tactic: 0xf1973f09f9ca8bf3 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xf1973f09f9ca8bf3 Time: 0.171593 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.117467 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.192512 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_interior_nhwc_tn_v1 Tactic: 0x992a591f6c1eb36f +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x992a591f6c1eb36f Time: 0.282039 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.17408 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.243858 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0x79a2c15a169f2ec9 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x79a2c15a169f2ec9 Time: 0.152137 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.300933 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.192073 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.157696 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.198071 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_interior_nhwc_tn_v1 Tactic: 0xdbe058db40209ee1 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xdbe058db40209ee1 Time: 0.1536 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_interior_nhwc_tn_v1 Tactic: 0x9d9e6402ba06ac05 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x9d9e6402ba06ac05 Time: 0.245609 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.155355 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.200411 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.149065 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.168667 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.31147 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.287305 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.261413 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.18549 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.163986 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.142629 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_interior_nhwc_tn_v1 Tactic: 0xc46b68b21152e8c1 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc46b68b21152e8c1 Time: 0.237275 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.136489 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x4a33d90483c0ec01 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x4a33d90483c0ec01 Time: 0.126537 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.208165 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.125294 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r1s1 Tactic: 0xb4ed47991b2d81ae +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xb4ed47991b2d81ae Time: 0.129609 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x9d78040b7e8c8ac7 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x9d78040b7e8c8ac7 Time: 0.147602 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r1s1 Tactic: 0xd80cb0f3373aef38 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xd80cb0f3373aef38 Time: 0.13277 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.124759 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.149061 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.114615 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_interior_nhwc_tn_v1 Tactic: 0xe3cad530d257946a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe3cad530d257946a Time: 0.197641 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.3072 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_interior_nhwc_tn_v1 Tactic: 0xe433b7de8e028d8e +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe433b7de8e028d8e Time: 0.175543 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.123904 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.131072 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0x12e96131b90aa494 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x12e96131b90aa494 Time: 0.115323 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.205531 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.207287 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.133211 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.16501 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x2e9f40fea3fe4d65 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x2e9f40fea3fe4d65 Time: 0.164718 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.132827 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.151991 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.11848 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.166619 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.107435 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_interior_nhwc_tn_v1 Tactic: 0xe93bad2778c92bdd +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe93bad2778c92bdd Time: 0.192366 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0xea50b6d3d87bf5dd +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xea50b6d3d87bf5dd Time: 0.124489 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.149504 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.159598 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.193536 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.186222 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.151662 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x23848f7cc4e20635 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x23848f7cc4e20635 Time: 0.126757 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.189879 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x8f25d6cdaeaaa100 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x8f25d6cdaeaaa100 Time: 0.156265 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x8e1e99c68a674ff4 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x8e1e99c68a674ff4 Time: 0.128219 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.127483 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.191049 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.123689 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.120393 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.128951 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.146871 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0xbb4ac900a7be8b4c +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xbb4ac900a7be8b4c Time: 0.18315 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.133111 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.126683 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0xfa5a19eb8211e798 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xfa5a19eb8211e798 Time: 0.104375 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_interior_nhwc_tn_v1 Tactic: 0x15e036703de3ebb6 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x15e036703de3ebb6 Time: 0.199241 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.38795 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.164279 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0xdf5651a32d9311a6 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xdf5651a32d9311a6 Time: 0.160183 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x2aa016c86360697f +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x2aa016c86360697f Time: 0.287451 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.294034 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.173787 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x3e2d344492eaa731 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3e2d344492eaa731 Time: 0.142121 +[03/18/2024-15:12:59] [V] [TRT] Fastest Tactic: 0xfa5a19eb8211e798 Time: 0.104375 +[03/18/2024-15:12:59] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xfa5a19eb8211e798 +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Half(1036800,1:8,5760,32) *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CudaDepthwiseConvolution) +[03/18/2024-15:12:59] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskGemmConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskFlattenConvolution) +[03/18/2024-15:12:59] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CaskConvolution) +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.29067 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.155941 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.140875 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.170423 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_interior_nhwc_tn_v1 Tactic: 0xeec2cfc9249c3239 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xeec2cfc9249c3239 Time: 0.166912 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.129463 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0x483db0113d970335 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x483db0113d970335 Time: 0.14107 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0x8d15f485c8c7f871 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x8d15f485c8c7f871 Time: 0.139785 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.155941 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_interior_nhwc_tn_v1 Tactic: 0xfb66471e53543444 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xfb66471e53543444 Time: 0.157842 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.171008 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.151845 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0x3f725d7f77411cdc +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3f725d7f77411cdc Time: 0.126098 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_interior_nhwc_tn_v1 Tactic: 0xc0df55afc74af7ab +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc0df55afc74af7ab Time: 0.330021 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_interior_nhwc_tn_v1 Tactic: 0x1f114e67977d5401 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x1f114e67977d5401 Time: 0.190025 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.169838 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0xc9d48aa637bf7810 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc9d48aa637bf7810 Time: 0.153746 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.145376 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.19456 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.259365 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_interior_nhwc_tn_v1 Tactic: 0xf1973f09f9ca8bf3 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xf1973f09f9ca8bf3 Time: 0.17013 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.117488 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.190757 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_interior_nhwc_tn_v1 Tactic: 0x992a591f6c1eb36f +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x992a591f6c1eb36f Time: 0.280283 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.171447 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.241664 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0x79a2c15a169f2ec9 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x79a2c15a169f2ec9 Time: 0.150089 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.246633 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.189294 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.156517 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.195762 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_interior_nhwc_tn_v1 Tactic: 0xdbe058db40209ee1 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xdbe058db40209ee1 Time: 0.15243 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_interior_nhwc_tn_v1 Tactic: 0x9d9e6402ba06ac05 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x9d9e6402ba06ac05 Time: 0.241915 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.151991 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.196178 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.145234 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.162377 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.298423 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.275602 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.251319 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.176421 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.157696 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.141093 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_interior_nhwc_tn_v1 Tactic: 0xc46b68b21152e8c1 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc46b68b21152e8c1 Time: 0.229669 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.132242 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x4a33d90483c0ec01 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x4a33d90483c0ec01 Time: 0.122645 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0x454d6448fb6e7fd1 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x454d6448fb6e7fd1 Time: 0.137216 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.199241 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.123888 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0x3ca70d6b51bf2164 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3ca70d6b51bf2164 Time: 0.152722 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0x8047bcfcebface4a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x8047bcfcebface4a Time: 0.122222 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0xe69f3e9fcc7b2069 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe69f3e9fcc7b2069 Time: 0.265801 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r1s1 Tactic: 0xb4ed47991b2d81ae +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xb4ed47991b2d81ae Time: 0.126903 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x9d78040b7e8c8ac7 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x9d78040b7e8c8ac7 Time: 0.146871 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r1s1 Tactic: 0xd80cb0f3373aef38 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xd80cb0f3373aef38 Time: 0.131803 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.125147 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.147895 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.109367 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_interior_nhwc_tn_v1 Tactic: 0xe3cad530d257946a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe3cad530d257946a Time: 0.198802 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.312174 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_interior_nhwc_tn_v1 Tactic: 0xe433b7de8e028d8e +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe433b7de8e028d8e Time: 0.172183 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0x3e55aa5fb58280dd +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3e55aa5fb58280dd Time: 0.123227 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.129623 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.130633 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0x12e96131b90aa494 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x12e96131b90aa494 Time: 0.119314 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0x5cf18273fea3db5c +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x5cf18273fea3db5c Time: 0.141385 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.205093 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.207726 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.13312 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0x7a738fe099ae3c1e +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x7a738fe099ae3c1e Time: 0.148041 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.160475 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x2e9f40fea3fe4d65 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x2e9f40fea3fe4d65 Time: 0.164864 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.132686 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.151698 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0xfd2247f786006d58 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xfd2247f786006d58 Time: 0.126391 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.123026 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.167643 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0xa2121200e08f5391 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xa2121200e08f5391 Time: 0.118784 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.107017 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_interior_nhwc_tn_v1 Tactic: 0xe93bad2778c92bdd +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe93bad2778c92bdd Time: 0.18827 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0xea50b6d3d87bf5dd +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xea50b6d3d87bf5dd Time: 0.120759 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.145248 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.156233 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.188709 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.182272 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.14848 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x23848f7cc4e20635 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x23848f7cc4e20635 Time: 0.12464 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.184027 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x8f25d6cdaeaaa100 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x8f25d6cdaeaaa100 Time: 0.152137 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x8e1e99c68a674ff4 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x8e1e99c68a674ff4 Time: 0.125077 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0x3eda3b336995a6f0 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3eda3b336995a6f0 Time: 0.126757 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.124197 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.186514 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0x361d222e42fcb76c +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x361d222e42fcb76c Time: 0.174971 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.120917 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.119794 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.127634 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.144384 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0xbb4ac900a7be8b4c +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xbb4ac900a7be8b4c Time: 0.180809 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.133193 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.125349 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0xfa5a19eb8211e798 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xfa5a19eb8211e798 Time: 0.104032 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_simple_t1r1s1 Tactic: 0x3fc555ff414cee06 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3fc555ff414cee06 Time: 0.120027 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_interior_nhwc_tn_v1 Tactic: 0x15e036703de3ebb6 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x15e036703de3ebb6 Time: 0.199387 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.290816 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.162821 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0xdf5651a32d9311a6 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xdf5651a32d9311a6 Time: 0.158427 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x2aa016c86360697f +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x2aa016c86360697f Time: 0.285403 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.292864 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.171008 +[03/18/2024-15:12:59] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r1s1 Tactic: 0x3e2d344492eaa731 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x3e2d344492eaa731 Time: 0.141166 +[03/18/2024-15:12:59] [V] [TRT] Fastest Tactic: 0xfa5a19eb8211e798 Time: 0.104032 +[03/18/2024-15:12:59] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xfa5a19eb8211e798 +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(259200,1:16,1440,8) -> Half(1036800,1:16,5760,32) long-strided *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Half(259200,1:16,1440,8) -> Half(518400,1:16,2880,16) *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_27 + Relu_28 (CublasConvolution) +[03/18/2024-15:12:59] [V] [TRT] CublasConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] =============== Computing costs for +[03/18/2024-15:12:59] [V] [TRT] *************** Autotuning format combination: Float(4147200,32400,180,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CudaDepthwiseConvolution) +[03/18/2024-15:12:59] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (FusedConvActConvolution) +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x000000000006ffff Time: 0.924818 +[03/18/2024-15:12:59] [V] [TRT] Fastest Tactic: 0x000000000006ffff Time: 0.924818 +[03/18/2024-15:12:59] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CudnnConvolution) +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.07813 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.868937 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x0000000000000002 Time: 1.41136 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x0000000000000005 Time: 22.6387 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x0000000000000038 Time: 1.54814 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x0000000000000039 Time: 0.966071 +[03/18/2024-15:12:59] [V] [TRT] Tactic: 0x000000000000003a Time: 1.50235 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x000000000000003d Time: 22.0376 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x0000000000000070 Time: 1.60066 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x0000000000000071 Time: 1.32111 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x0000000000000072 Time: 1.78219 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x0000000000000075 Time: 21.9336 +[03/18/2024-15:13:00] [V] [TRT] Fastest Tactic: 0x0000000000000001 Time: 0.868937 +[03/18/2024-15:13:00] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskGemmConvolution) +[03/18/2024-15:13:00] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:00] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskFlattenConvolution) +[03/18/2024-15:13:00] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:00] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskConvolution) +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 1.37362 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 0.961682 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.96373 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.847173 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 0.888539 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 1.93068 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 2.79523 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 0.987429 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 1.44208 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.886638 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 1.46856 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 1.56935 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x4727434768e46395 Time: 1.12625 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 1.01698 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 1.07067 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 1.58749 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.955685 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 1.11206 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 1.17058 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 1.87904 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.974409 +[03/18/2024-15:13:00] [V] [TRT] Fastest Tactic: 0x503619c69ae500ff Time: 0.847173 +[03/18/2024-15:13:00] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:00] [V] [TRT] *************** Autotuning format combination: Float(4147200,1,23040,128) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:13:00] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskFlattenConvolution) +[03/18/2024-15:13:00] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:00] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskConvolution) +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x27b316f52c109002 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x27b316f52c109002 Time: 0.977335 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x128_relu_exp_medium_nhwc_tn_v1 Tactic: 0xd9031472c05adf51 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xd9031472c05adf51 Time: 0.906094 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x3e2b881168d9689d +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x3e2b881168d9689d Time: 0.863086 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0xf90060ce8193b811 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xf90060ce8193b811 Time: 0.882249 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0xbdfdef6b84f7ccc9 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xbdfdef6b84f7ccc9 Time: 0.966802 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x412c44dfeaf9161d +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x412c44dfeaf9161d Time: 0.964169 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x7bc32c782b800c48 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x7bc32c782b800c48 Time: 0.863378 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 1.31877 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 0.979383 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 1.23845 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.866743 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x3e191488237fab8f +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x3e191488237fab8f Time: 1.31028 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 1.58398 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 1.87436 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 0.958757 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 1.99037 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.883566 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.79973 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x128_relu_exp_large_nhwc_tn_v1 Tactic: 0xca7eeb8d9143d738 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xca7eeb8d9143d738 Time: 1.17307 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 1.0436 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 0.735378 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x128_relu_exp_small_nhwc_tn_v1 Tactic: 0x5030121339a48bf3 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x5030121339a48bf3 Time: 1.0654 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 1.56496 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 0.836901 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 1.47836 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0x634e99502974e4da +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x634e99502974e4da Time: 0.914725 +[03/18/2024-15:13:00] [V] [TRT] Fastest Tactic: 0xf48db81f02eca9ee Time: 0.735378 +[03/18/2024-15:13:00] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:00] [V] [TRT] *************** Autotuning format combination: Float(1036800,1:4,5760,32) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:13:00] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CudaDepthwiseConvolution) +[03/18/2024-15:13:00] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:00] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskGemmConvolution) +[03/18/2024-15:13:00] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:00] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskFlattenConvolution) +[03/18/2024-15:13:00] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:00] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskConvolution) +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 0.650094 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.8328 +[03/18/2024-15:13:00] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.735698 +[03/18/2024-15:13:00] [V] [TRT] Fastest Tactic: 0x999e005e3b016ea6 Time: 0.650094 +[03/18/2024-15:13:00] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:00] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400,180,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:13:00] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CudnnConvolution) +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.27269 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x0000000000000001 Time: 1.13093 +[03/18/2024-15:13:00] [V] [TRT] Tactic: 0x0000000000000002 Time: 1.12947 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x0000000000000005 Time: 22.0676 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x0000000000000038 Time: 1.44779 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000000003a Time: 1.33617 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000000003d Time: 21.9212 +[03/18/2024-15:13:01] [V] [TRT] Fastest Tactic: 0x0000000000000002 Time: 1.12947 +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskGemmConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskFlattenConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000002 +[03/18/2024-15:13:01] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400:2,180,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (FusedConvActConvolution) +[03/18/2024-15:13:01] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskFlattenConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:4,5760,32) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskFlattenConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskFlattenConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] *************** Autotuning format combination: Half(518400,1:8,2880,16) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CudaDepthwiseConvolution) +[03/18/2024-15:13:01] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskGemmConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskFlattenConvolution) +[03/18/2024-15:13:01] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_44 + Relu_45 (CaskConvolution) +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.196608 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.154478 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.153006 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.170277 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.143945 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.163694 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.162816 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.135008 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.155648 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.174958 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.144073 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.138167 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.135328 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.137655 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.210222 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.150967 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.173641 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.157696 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.194267 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.151845 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.196169 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.166912 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.163547 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.157257 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.193271 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.194706 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.162962 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.155063 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.161353 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.182857 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.168667 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.169399 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.160329 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.172617 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.202606 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.152704 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.207433 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.195145 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.186222 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.151259 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.184466 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.196023 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.173166 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.150089 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.197925 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.154903 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.168215 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.150528 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.15989 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.144384 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.150382 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.148187 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.144969 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.147479 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.18827 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.137001 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.335433 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.167497 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.170423 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.133625 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.165408 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.150066 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.150249 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.148187 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.188855 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.183003 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.163109 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.191342 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.132096 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.164279 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.149399 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.188562 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.191342 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.167643 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.139705 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.140727 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.192782 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.189294 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.136923 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.152283 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.185344 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.147593 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.172919 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.155063 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.151259 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.130784 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.150382 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.151991 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.177006 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.139337 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.168521 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.151698 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.136704 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.168229 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.147497 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.141751 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.182272 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.332946 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.192073 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.189294 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.26229 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.169691 +[03/18/2024-15:13:01] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.146286 +[03/18/2024-15:13:01] [V] [TRT] Fastest Tactic: 0x17ebf0c9f418f10a Time: 0.130784 +[03/18/2024-15:13:01] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:01] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:01] [V] [TRT] *************** Autotuning format combination: Float(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CudaDepthwiseConvolution) +[03/18/2024-15:13:01] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:01] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (FusedConvActConvolution) +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000007ffff Time: 1.55575 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x00000000000affff Time: 1.33398 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x00000000000effff Time: 1.59188 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x00000000000fffff Time: 1.8786 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000019ffff Time: 1.65449 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x00000000001affff Time: 1.92219 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000024ffff Time: 2.08911 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000027ffff Time: 1.87538 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x00000000002dffff Time: 1.45642 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000036ffff Time: 1.9592 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x00000000004cffff Time: 1.50981 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000062ffff Time: 1.4554 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x00000000006effff Time: 1.75481 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000077ffff Time: 1.86631 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000086ffff Time: 2.31044 +[03/18/2024-15:13:01] [V] [TRT] Tactic: 0x000000000089ffff Time: 1.45949 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x000000000097ffff Time: 2.19922 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x000000000098ffff Time: 1.55838 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x00000000009fffff Time: 1.67965 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000a2ffff Time: 1.59612 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000a4ffff Time: 1.89162 +[03/18/2024-15:13:02] [V] [TRT] Fastest Tactic: 0x00000000000affff Time: 1.33398 +[03/18/2024-15:13:02] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CudnnConvolution) +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.37641 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000001 Time: 1.51157 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000002 Time: 2.77738 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000005 Time: 12.0199 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000006 Time: 1.57901 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000038 Time: 2.92805 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000039 Time: 1.65741 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x000000000000003a Time: 2.8299 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x000000000000003d Time: 11.8256 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x000000000000003e Time: 1.6501 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000070 Time: 2.48349 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000071 Time: 2.46506 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000072 Time: 2.58445 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000075 Time: 11.9106 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x0000000000000076 Time: 1.50411 +[03/18/2024-15:13:02] [V] [TRT] Fastest Tactic: 0x0000000000000076 Time: 1.50411 +[03/18/2024-15:13:02] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskGemmConvolution) +[03/18/2024-15:13:02] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:02] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskFlattenConvolution) +[03/18/2024-15:13:02] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:02] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskConvolution) +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 2.22471 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 1.66254 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 2.00104 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 1.21711 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 1.92761 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 1.87816 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 3.76557 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 5.767 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 1.90742 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 2.52562 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 1.77986 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 3.28602 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 2.91869 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0x4727434768e46395 Time: 2.21755 +[03/18/2024-15:13:02] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:02] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 1.93858 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 1.75645 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 2.75193 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 2.26597 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 1.9592 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 2.00689 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 3.53894 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 1.9848 +[03/18/2024-15:13:03] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 1.21711 +[03/18/2024-15:13:03] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:03] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,23040,256) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:13:03] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskFlattenConvolution) +[03/18/2024-15:13:03] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:03] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskConvolution) +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x27b316f52c109002 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x27b316f52c109002 Time: 1.65288 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x128_relu_exp_medium_nhwc_tn_v1 Tactic: 0xd9031472c05adf51 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0xd9031472c05adf51 Time: 1.78951 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x3e2b881168d9689d +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x3e2b881168d9689d Time: 1.71769 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0xf90060ce8193b811 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0xf90060ce8193b811 Time: 1.88226 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0xbdfdef6b84f7ccc9 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0xbdfdef6b84f7ccc9 Time: 1.92322 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x412c44dfeaf9161d +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x412c44dfeaf9161d Time: 1.92951 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x7bc32c782b800c48 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x7bc32c782b800c48 Time: 1.85461 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 2.54683 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 2.27138 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 2.83807 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 1.68492 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x3e191488237fab8f +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x3e191488237fab8f Time: 2.25573 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 3.14968 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 3.64708 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 1.8758 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 3.8359 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 1.91005 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 1.77474 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x128_relu_exp_large_nhwc_tn_v1 Tactic: 0xca7eeb8d9143d738 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0xca7eeb8d9143d738 Time: 2.08692 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 2.03542 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 1.70993 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x128_relu_exp_small_nhwc_tn_v1 Tactic: 0x5030121339a48bf3 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x5030121339a48bf3 Time: 2.05385 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 2.82419 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 1.89135 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 3.37232 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0x634e99502974e4da +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x634e99502974e4da Time: 1.89717 +[03/18/2024-15:13:03] [V] [TRT] Fastest Tactic: 0x27b316f52c109002 Time: 1.65288 +[03/18/2024-15:13:03] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x27b316f52c109002 +[03/18/2024-15:13:03] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:13:03] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CudaDepthwiseConvolution) +[03/18/2024-15:13:03] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:03] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskGemmConvolution) +[03/18/2024-15:13:03] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:03] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskFlattenConvolution) +[03/18/2024-15:13:03] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:03] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskConvolution) +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 1.30238 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 1.24475 +[03/18/2024-15:13:03] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 1.04155 +[03/18/2024-15:13:03] [V] [TRT] Fastest Tactic: 0xb443c221fcb1565b Time: 1.04155 +[03/18/2024-15:13:03] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:03] [V] [TRT] *************** Autotuning format combination: Half(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:13:03] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CudnnConvolution) +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.14395 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x0000000000000001 Time: 1.78161 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x0000000000000002 Time: 2.45292 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x0000000000000005 Time: 11.8383 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x0000000000000006 Time: 1.37904 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x0000000000000038 Time: 2.66913 +[03/18/2024-15:13:03] [V] [TRT] Tactic: 0x000000000000003a Time: 2.32082 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x000000000000003d Time: 11.835 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x000000000000003e Time: 1.63167 +[03/18/2024-15:13:04] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 1.37904 +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskGemmConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000006 +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(1036800,8100:2,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (FusedConvActConvolution) +[03/18/2024-15:13:04] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CudaDepthwiseConvolution) +[03/18/2024-15:13:04] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskGemmConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_46 + Relu_47 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.342162 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.24459 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.244736 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.271653 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.246638 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.380197 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.3008 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.238446 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.328411 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.346258 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.33397 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.263899 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.261851 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.266386 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.302519 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.251904 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.294327 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.258341 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.290377 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.336448 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.294327 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.287159 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.264046 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.261307 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.395122 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.283794 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.260242 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.341723 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.262875 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.329874 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.33675 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.289179 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.263785 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.298569 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.34933 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.255561 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.297545 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.272969 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.277797 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.253367 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.391867 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.343022 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.307054 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.252928 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.403895 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.252379 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.298277 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.370542 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.250295 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.238153 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.258048 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.2624 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.254542 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.296375 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.328704 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.250181 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.505271 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.297399 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.306615 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.253513 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.294181 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.257463 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.252521 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.253074 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.462249 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.376251 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.374373 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.396142 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.244882 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.34288 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.253513 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.376978 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.380489 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.301934 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.257755 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.25995 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.295058 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.387241 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.258171 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.283502 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.338651 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.249417 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.294766 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.288329 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.262437 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.249563 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.258231 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.282496 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.339675 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.259072 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.363227 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.263314 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.252343 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.315246 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.261851 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.253952 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.333824 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.577975 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.341431 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.326071 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.497664 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.312613 +[03/18/2024-15:13:04] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.249417 +[03/18/2024-15:13:04] [V] [TRT] Fastest Tactic: 0x263a38afd75e3a43 Time: 0.238153 +[03/18/2024-15:13:04] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:04] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,23040,256) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(1036800,8100:2,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_48 + Relu_49 (FusedConvActConvolution) +[03/18/2024-15:13:04] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_48 + Relu_49 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_48 + Relu_49 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_48 + Relu_49 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_48 + Relu_49 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_48 + Relu_49 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_48 + Relu_49 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:13:04] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,23040,256) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(1036800,8100:2,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_50 + Relu_51 (FusedConvActConvolution) +[03/18/2024-15:13:04] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_50 + Relu_51 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_50 + Relu_51 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_50 + Relu_51 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_50 + Relu_51 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_50 + Relu_51 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_50 + Relu_51 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:13:04] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,23040,256) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(1036800,8100:2,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_52 + Relu_53 (FusedConvActConvolution) +[03/18/2024-15:13:04] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_52 + Relu_53 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_52 + Relu_53 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_52 + Relu_53 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_52 + Relu_53 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_52 + Relu_53 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_52 + Relu_53 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:13:04] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(2073600,8100,90,1) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,23040,256) -> Float(2073600,1,23040,256) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,5760,64) -> Float(518400,1:4,5760,64) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(2073600,8100,90,1) -> Half(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(1036800,8100:2,90,1) -> Half(1036800,8100:2,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_54 + Relu_55 (FusedConvActConvolution) +[03/18/2024-15:13:04] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_54 + Relu_55 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_54 + Relu_55 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,5760,64) -> Half(518400,1:4,5760,64) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_54 + Relu_55 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_54 + Relu_55 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Float(2073600,8100,90,1) *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_54 + Relu_55 (CaskFlattenConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: Conv_54 + Relu_55 (CaskConvolution) +[03/18/2024-15:13:04] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Half(259200,1:8,2880,32) *************** +[03/18/2024-15:13:04] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:04] [V] [TRT] *************** Autotuning format combination: Float(2073600,8100,90,1) -> Float(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:04] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.21344 +[03/18/2024-15:13:04] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 1.21344 +[03/18/2024-15:13:04] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58: 24 available tactics, 19 unparsable, 2 pruned, 22 remaining after tactic pruning. +[03/18/2024-15:13:04] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskGemmDeconvolution) +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize128x64x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000203f4 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x00000000000203f4 Time: 1.25279 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: ampere_sgemm_64x32_sliced1x4_relu_nn_v1 Tactic: 0x00000000000206dc numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x00000000000206dc Time: 1.40052 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize128x32x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000204f8 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x00000000000204f8 Time: 1.74694 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize128x128x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000204d8 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x00000000000204d8 Time: 1.90128 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize32x128x8_stage3_warpsize1x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000204b1 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x00000000000204b1 Time: 1.20613 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize64x128x8_stage3_warpsize1x4x1_ffma_aligna4_alignc4 Tactic: 0x00000000000204a7 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x00000000000204a7 Time: 9.54865 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize64x256x8_stage3_warpsize1x4x1_ffma_aligna4_alignc4 Tactic: 0x000000000002045f numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x000000000002045f Time: 4.21976 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize256x64x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x000000000002044a numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x000000000002044a Time: 1.3018 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize64x32x8_stage3_warpsize1x2x1_ffma_aligna4_alignc4 Tactic: 0x000000000002042b numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x000000000002042b Time: 1.83647 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: ampere_sgemm_64x32_sliced1x4_nn_v1 Tactic: 0x0000000000020095 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x0000000000020095 Time: 1.34232 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize256x128x8_stage3_warpsize4x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000203b2 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x00000000000203b2 Time: 1.24098 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize32x64x8_stage3_warpsize1x2x1_ffma_aligna4_alignc4 Tactic: 0x000000000002033f numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x000000000002033f Time: 1.41356 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize128x256x8_stage3_warpsize2x4x1_ffma_aligna4_alignc4 Tactic: 0x00000000000202f2 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x00000000000202f2 Time: 1.30341 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize32x32x8_stage3_warpsize1x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000202d1 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x00000000000202d1 Time: 1.70189 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize64x64x8_stage3_warpsize1x4x1_ffma_aligna4_alignc4 Tactic: 0x000000000002023d numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x000000000002023d Time: 1.3037 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: ampere_sgemm_128x32_sliced1x4_relu_nn_v1 Tactic: 0x000000000002020e numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:04] [V] [TRT] Tactic: 0x000000000002020e Time: 1.63196 +[03/18/2024-15:13:04] [V] [TRT] Set Tactic Name: ampere_sgemm_32x32_sliced1x4_relu_nn_v1 Tactic: 0x0000000000020208 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0000000000020208 Time: 1.66385 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: ampere_sgemm_128x32_sliced1x4_nn_v1 Tactic: 0x00000000000201a6 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000201a6 Time: 1.5714 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: ampere_sgemm_32x32_sliced1x4_nn_v1 Tactic: 0x0000000000020161 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0000000000020161 Time: 1.67102 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize256x64x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x000000000204044a numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x000000000204044a Time: 2.08896 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize64x256x8_stage3_warpsize1x4x1_ffma_aligna4_alignc4 Tactic: 0x000000000204045f numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x000000000204045f Time: 1.30501 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize128x128x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000020404d8 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000020404d8 Time: 1.36967 +[03/18/2024-15:13:05] [V] [TRT] Fastest Tactic: 0x00000000000204b1 Time: 1.20613 +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:05] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:05] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm50_xmma_deconv_generic_f32f32_f32_f32_nchwkcrs_nchw Tactic: 0x0f630dccfe13bf53 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0f630dccfe13bf53 Time: 10000 +[03/18/2024-15:13:05] [V] [TRT] Fastest Tactic: 0x0f630dccfe13bf53 Time: 10000 +[03/18/2024-15:13:05] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskGemmDeconvolution Tactic: 0x00000000000204b1 +[03/18/2024-15:13:05] [V] [TRT] *************** Autotuning format combination: Float(2073600,8100,90,1) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.78692 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0000000000000001 Time: 1.42775 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0000000000000003 Time: 43.6244 +[03/18/2024-15:13:05] [V] [TRT] Fastest Tactic: 0x0000000000000001 Time: 1.42775 +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.30473 +[03/18/2024-15:13:05] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 2.30473 +[03/18/2024-15:13:05] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58: 24 available tactics, 19 unparsable, 2 pruned, 22 remaining after tactic pruning. +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskGemmDeconvolution) +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize128x64x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000203f4 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000203f4 Time: 1.49928 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: ampere_sgemm_64x32_sliced1x4_relu_nn_v1 Tactic: 0x00000000000206dc numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000206dc Time: 1.85944 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize128x32x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000204f8 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000204f8 Time: 1.92936 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize128x128x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000204d8 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000204d8 Time: 1.2528 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize32x128x8_stage3_warpsize1x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000204b1 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000204b1 Time: 1.2573 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize64x128x8_stage3_warpsize1x4x1_ffma_aligna4_alignc4 Tactic: 0x00000000000204a7 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000204a7 Time: 1.20905 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize64x256x8_stage3_warpsize1x4x1_ffma_aligna4_alignc4 Tactic: 0x000000000002045f numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x000000000002045f Time: 1.28585 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize256x64x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x000000000002044a numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x000000000002044a Time: 1.24899 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize64x32x8_stage3_warpsize1x2x1_ffma_aligna4_alignc4 Tactic: 0x000000000002042b numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x000000000002042b Time: 1.96359 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: ampere_sgemm_64x32_sliced1x4_nn_v1 Tactic: 0x0000000000020095 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0000000000020095 Time: 1.54565 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize256x128x8_stage3_warpsize4x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000203b2 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000203b2 Time: 1.27064 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize32x64x8_stage3_warpsize1x2x1_ffma_aligna4_alignc4 Tactic: 0x000000000002033f numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x000000000002033f Time: 1.52152 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize128x256x8_stage3_warpsize2x4x1_ffma_aligna4_alignc4 Tactic: 0x00000000000202f2 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000202f2 Time: 1.12216 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize32x32x8_stage3_warpsize1x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000000202d1 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000202d1 Time: 1.92584 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize64x64x8_stage3_warpsize1x4x1_ffma_aligna4_alignc4 Tactic: 0x000000000002023d numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x000000000002023d Time: 1.35665 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: ampere_sgemm_128x32_sliced1x4_relu_nn_v1 Tactic: 0x000000000002020e numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x000000000002020e Time: 1.88138 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: ampere_sgemm_32x32_sliced1x4_relu_nn_v1 Tactic: 0x0000000000020208 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0000000000020208 Time: 1.70774 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: ampere_sgemm_128x32_sliced1x4_nn_v1 Tactic: 0x00000000000201a6 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000000201a6 Time: 1.46827 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: ampere_sgemm_32x32_sliced1x4_nn_v1 Tactic: 0x0000000000020161 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0000000000020161 Time: 1.78907 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize256x64x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x000000000204044a numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x000000000204044a Time: 1.95745 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize64x256x8_stage3_warpsize1x4x1_ffma_aligna4_alignc4 Tactic: 0x000000000204045f numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x000000000204045f Time: 1.50278 +[03/18/2024-15:13:05] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f32f32_f32f32_f32_nn_n_tilesize128x128x8_stage3_warpsize2x2x1_ffma_aligna4_alignc4 Tactic: 0x00000000020404d8 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x00000000020404d8 Time: 1.48378 +[03/18/2024-15:13:05] [V] [TRT] Fastest Tactic: 0x00000000000202f2 Time: 1.12216 +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:05] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:05] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm50_xmma_deconv_generic_f32f32_f32_f32_nchwkcrs_nchw Tactic: 0x0f630dccfe13bf53 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0f630dccfe13bf53 Time: 10000 +[03/18/2024-15:13:05] [V] [TRT] Fastest Tactic: 0x0f630dccfe13bf53 Time: 10000 +[03/18/2024-15:13:05] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskGemmDeconvolution Tactic: 0x00000000000202f2 +[03/18/2024-15:13:05] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,23040,256) -> Float(16588800,1,92160,512) long-strided *************** +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:05] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:05] [V] [TRT] GemmDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:05] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:05] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:05] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0xba791a7991b0361c +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0xba791a7991b0361c Time: 0.94603 +[03/18/2024-15:13:05] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x55c5f197e3b7e8aa +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x55c5f197e3b7e8aa Time: 0.939154 +[03/18/2024-15:13:05] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb1d8242d50afdff0 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0xb1d8242d50afdff0 Time: 2.44549 +[03/18/2024-15:13:05] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x0af5b8971b78dc1f +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x0af5b8971b78dc1f Time: 1.42641 +[03/18/2024-15:13:05] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x6f63be3116a0cf3a +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x6f63be3116a0cf3a Time: 1.93946 +[03/18/2024-15:13:05] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x32x8_stage3_warpsize1x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0xf7c9fe3fcf824969 +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0xf7c9fe3fcf824969 Time: 1.34627 +[03/18/2024-15:13:05] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm86_xmma_deconv_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x256x32_stage2_warpsize2x4x1_g1_tensor16x8x8 Tactic: 0x4298039fe7d925bf +[03/18/2024-15:13:05] [V] [TRT] Tactic: 0x4298039fe7d925bf Time: 1.85841 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x128x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x24bd5d7c8284eeec +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x24bd5d7c8284eeec Time: 2.48013 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x1a82ab99d94518f2 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x1a82ab99d94518f2 Time: 0.971045 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_strided Tactic: 0xa17395d1f0a7b52b +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xa17395d1f0a7b52b Time: 0.592896 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x043c81cea95f3c97 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x043c81cea95f3c97 Time: 1.48129 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x14499f757787b157 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x14499f757787b157 Time: 4.37892 +[03/18/2024-15:13:06] [V] [TRT] Fastest Tactic: 0xa17395d1f0a7b52b Time: 0.592896 +[03/18/2024-15:13:06] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskDeconvolutionV2 Tactic: 0xa17395d1f0a7b52b +[03/18/2024-15:13:06] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,23040,256) -> Float(8294400,1,46080,256) *************** +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] GemmDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0xba791a7991b0361c +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xba791a7991b0361c Time: 0.99723 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x55c5f197e3b7e8aa +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x55c5f197e3b7e8aa Time: 1.14015 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb1d8242d50afdff0 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xb1d8242d50afdff0 Time: 2.84248 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x0af5b8971b78dc1f +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0af5b8971b78dc1f Time: 1.3982 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x6f63be3116a0cf3a +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x6f63be3116a0cf3a Time: 1.88299 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x32x8_stage3_warpsize1x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0xf7c9fe3fcf824969 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xf7c9fe3fcf824969 Time: 1.28088 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm86_xmma_deconv_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x256x32_stage2_warpsize2x4x1_g1_tensor16x8x8 Tactic: 0x4298039fe7d925bf +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x4298039fe7d925bf Time: 1.89264 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x128x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x24bd5d7c8284eeec +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x24bd5d7c8284eeec Time: 2.44692 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x1a82ab99d94518f2 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x1a82ab99d94518f2 Time: 0.899195 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_strided Tactic: 0xa17395d1f0a7b52b +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xa17395d1f0a7b52b Time: 0.652873 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x043c81cea95f3c97 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x043c81cea95f3c97 Time: 1.50411 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x14499f757787b157 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x14499f757787b157 Time: 4.51072 +[03/18/2024-15:13:06] [V] [TRT] Fastest Tactic: 0xa17395d1f0a7b52b Time: 0.652873 +[03/18/2024-15:13:06] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskDeconvolutionV2 Tactic: 0xa17395d1f0a7b52b +[03/18/2024-15:13:06] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,5760,64) -> Float(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] GemmDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0xba791a7991b0361c +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xba791a7991b0361c Time: 0.961975 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x55c5f197e3b7e8aa +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x55c5f197e3b7e8aa Time: 1.09436 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb1d8242d50afdff0 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xb1d8242d50afdff0 Time: 2.9835 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x0af5b8971b78dc1f +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0af5b8971b78dc1f Time: 1.34085 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x6f63be3116a0cf3a +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x6f63be3116a0cf3a Time: 2.03527 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x32x8_stage3_warpsize1x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0xf7c9fe3fcf824969 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xf7c9fe3fcf824969 Time: 1.29697 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm86_xmma_deconv_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x256x32_stage2_warpsize2x4x1_g1_tensor16x8x8 Tactic: 0x4298039fe7d925bf +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x4298039fe7d925bf Time: 2.06892 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x128x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x24bd5d7c8284eeec +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x24bd5d7c8284eeec Time: 2.43405 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x1a82ab99d94518f2 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x1a82ab99d94518f2 Time: 0.930231 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_strided Tactic: 0xa17395d1f0a7b52b +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xa17395d1f0a7b52b Time: 0.587191 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x043c81cea95f3c97 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x043c81cea95f3c97 Time: 1.5281 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x14499f757787b157 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x14499f757787b157 Time: 4.60756 +[03/18/2024-15:13:06] [V] [TRT] Fastest Tactic: 0xa17395d1f0a7b52b Time: 0.587191 +[03/18/2024-15:13:06] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskDeconvolutionV2 Tactic: 0xa17395d1f0a7b52b +[03/18/2024-15:13:06] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,5760,64) -> Float(2073600,1:4,11520,64) *************** +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] GemmDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0xba791a7991b0361c +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xba791a7991b0361c Time: 0.984795 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x55c5f197e3b7e8aa +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x55c5f197e3b7e8aa Time: 1.00513 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb1d8242d50afdff0 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xb1d8242d50afdff0 Time: 2.98584 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x0af5b8971b78dc1f +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0af5b8971b78dc1f Time: 1.40537 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x6f63be3116a0cf3a +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x6f63be3116a0cf3a Time: 2.10695 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x32x8_stage3_warpsize1x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0xf7c9fe3fcf824969 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xf7c9fe3fcf824969 Time: 1.44971 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm86_xmma_deconv_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x256x32_stage2_warpsize2x4x1_g1_tensor16x8x8 Tactic: 0x4298039fe7d925bf +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x4298039fe7d925bf Time: 2.08591 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x128x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x24bd5d7c8284eeec +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x24bd5d7c8284eeec Time: 2.41807 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x1a82ab99d94518f2 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x1a82ab99d94518f2 Time: 0.802523 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_strided Tactic: 0xa17395d1f0a7b52b +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0xa17395d1f0a7b52b Time: 0.58997 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_strided_aligna4_alignc4 Tactic: 0x043c81cea95f3c97 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x043c81cea95f3c97 Time: 1.64688 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x14499f757787b157 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x14499f757787b157 Time: 4.66271 +[03/18/2024-15:13:06] [V] [TRT] Fastest Tactic: 0xa17395d1f0a7b52b Time: 0.58997 +[03/18/2024-15:13:06] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskDeconvolutionV2 Tactic: 0xa17395d1f0a7b52b +[03/18/2024-15:13:06] [V] [TRT] *************** Autotuning format combination: Half(2073600,8100,90,1) -> Half(16588800,32400,180,1) long-strided *************** +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.742839 +[03/18/2024-15:13:06] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.742839 +[03/18/2024-15:13:06] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58: 23 available tactics, 16 unparsable, 3 pruned, 20 remaining after tactic pruning. +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskGemmDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize128x64x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000000203f8 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x00000000000203f8 Time: 0.999131 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize64x128x8_stage3_warpsize1x4x1_ffma_aligna2_alignc2 Tactic: 0x000000000002053c numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x000000000002053c Time: 0.964901 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize256x64x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000000204fc numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x00000000000204fc Time: 0.963881 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize64x64x8_stage3_warpsize1x4x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020545 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0000000000020545 Time: 1.16326 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize128x128x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000000204e6 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x00000000000204e6 Time: 1.01669 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: ampere_hgemm_128x64_nn_v0 Tactic: 0x00000000000204e5 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x00000000000204e5 Time: 0.746949 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize32x64x8_stage3_warpsize1x2x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020436 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0000000000020436 Time: 1.46476 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize32x32x8_stage3_warpsize1x2x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020419 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0000000000020419 Time: 1.47399 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: ampere_hgemm_256x128_nn_v0 Tactic: 0x00000000000205ba numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x00000000000205ba Time: 0.834414 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize128x256x8_stage3_warpsize2x4x1_ffma_aligna2_alignc2 Tactic: 0x000000000002033e numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x000000000002033e Time: 1.15712 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize128x32x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x000000000002031e numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x000000000002031e Time: 1.24665 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize32x128x8_stage3_warpsize1x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000000202a3 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x00000000000202a3 Time: 1.2506 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize64x32x8_stage3_warpsize1x2x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020299 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0000000000020299 Time: 1.41224 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize64x256x8_stage3_warpsize1x4x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020717 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0000000000020717 Time: 1.1776 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize256x128x8_stage3_warpsize4x2x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020267 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0000000000020267 Time: 1.01435 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: ampere_hgemm_128x128_nn_v0 Tactic: 0x00000000000201d9 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x00000000000201d9 Time: 0.906679 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize256x64x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000020404fc numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x00000000020404fc Time: 1.48656 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize64x256x8_stage3_warpsize1x4x1_ffma_aligna2_alignc2 Tactic: 0x0000000002040717 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0000000002040717 Time: 1.3391 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize128x128x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000020404e6 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x00000000020404e6 Time: 1.31994 +[03/18/2024-15:13:06] [V] [TRT] Set Tactic Name: ampere_hgemm_128x128_nn_v0 Tactic: 0x00000000020401d9 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x00000000020401d9 Time: 0.788471 +[03/18/2024-15:13:06] [V] [TRT] Fastest Tactic: 0x00000000000204e5 Time: 0.746949 +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:06] [V] [TRT] CaskDeconvolutionV2 has no valid tactics for this config, skipping +[03/18/2024-15:13:06] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: GemmDeconvolution Tactic: 0x0000000000000000 +[03/18/2024-15:13:06] [V] [TRT] *************** Autotuning format combination: Half(2073600,8100,90,1) -> Half(8294400,32400,180,1) *************** +[03/18/2024-15:13:06] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:06] [V] [TRT] Tactic: 0x0000000000000000 Time: 1.93653 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000000001 Time: 4.98015 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000000003 Time: 43.4627 +[03/18/2024-15:13:07] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 1.93653 +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.654921 +[03/18/2024-15:13:07] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.654921 +[03/18/2024-15:13:07] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58: 23 available tactics, 16 unparsable, 3 pruned, 20 remaining after tactic pruning. +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskGemmDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize128x64x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000000203f8 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000203f8 Time: 1.03658 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize64x128x8_stage3_warpsize1x4x1_ffma_aligna2_alignc2 Tactic: 0x000000000002053c numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002053c Time: 0.985088 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize256x64x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000000204fc numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000204fc Time: 0.973531 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize64x64x8_stage3_warpsize1x4x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020545 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020545 Time: 1.12 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize128x128x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000000204e6 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000204e6 Time: 1.16487 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_hgemm_128x64_nn_v0 Tactic: 0x00000000000204e5 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000204e5 Time: 0.746642 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize32x64x8_stage3_warpsize1x2x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020436 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020436 Time: 1.24167 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize32x32x8_stage3_warpsize1x2x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020419 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020419 Time: 1.43097 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_hgemm_256x128_nn_v0 Tactic: 0x00000000000205ba numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000205ba Time: 1.0161 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize128x256x8_stage3_warpsize2x4x1_ffma_aligna2_alignc2 Tactic: 0x000000000002033e numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002033e Time: 1.26186 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize128x32x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x000000000002031e numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002031e Time: 1.27005 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize32x128x8_stage3_warpsize1x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000000202a3 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000202a3 Time: 1.30515 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize64x32x8_stage3_warpsize1x2x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020299 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020299 Time: 1.28805 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize64x256x8_stage3_warpsize1x4x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020717 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020717 Time: 1.2819 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize256x128x8_stage3_warpsize4x2x1_ffma_aligna2_alignc2 Tactic: 0x0000000000020267 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020267 Time: 1.3214 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_hgemm_128x128_nn_v0 Tactic: 0x00000000000201d9 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000201d9 Time: 0.830318 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize256x64x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000020404fc numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000020404fc Time: 1.27985 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize64x256x8_stage3_warpsize1x4x1_ffma_aligna2_alignc2 Tactic: 0x0000000002040717 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000002040717 Time: 1.32345 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f32f32_f32_nn_n_tilesize128x128x8_stage3_warpsize2x2x1_ffma_aligna2_alignc2 Tactic: 0x00000000020404e6 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000020404e6 Time: 1.36821 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_hgemm_128x128_nn_v0 Tactic: 0x00000000020401d9 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000020401d9 Time: 0.803657 +[03/18/2024-15:13:07] [V] [TRT] Fastest Tactic: 0x00000000000204e5 Time: 0.746642 +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:07] [V] [TRT] CaskDeconvolutionV2 has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: GemmDeconvolution Tactic: 0x0000000000000000 +[03/18/2024-15:13:07] [V] [TRT] *************** Autotuning format combination: Half(1036800,8100:2,90,1) -> Half(8294400,32400:2,180,1) long-strided *************** +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.722651 +[03/18/2024-15:13:07] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.722651 +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: GemmDeconvolution Tactic: 0x0000000000000000 +[03/18/2024-15:13:07] [V] [TRT] *************** Autotuning format combination: Half(1036800,8100:2,90,1) -> Half(4147200,32400:2,180,1) *************** +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.697344 +[03/18/2024-15:13:07] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.697344 +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: GemmDeconvolution Tactic: 0x0000000000000000 +[03/18/2024-15:13:07] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,5760,64) -> Half(4147200,1:4,23040,128) long-strided *************** +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] GemmDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:07] [V] [TRT] CaskDeconvolutionV2 has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,5760,64) -> Half(2073600,1:4,11520,64) *************** +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] GemmDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:07] [V] [TRT] CaskDeconvolutionV2 has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Half(2073600,1:8,11520,64) long-strided *************** +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.305701 +[03/18/2024-15:13:07] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.305701 +[03/18/2024-15:13:07] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58: 62 available tactics, 44 unparsable, 9 pruned, 53 remaining after tactic pruning. +[03/18/2024-15:13:07] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskGemmDeconvolution) +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x128x64_stage3_warpsize2x2x1_tensor16x8x16 Tactic: 0x00000000000204f2 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000204f2 Time: 0.356937 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x128_ldg8_relu_nn_v1 Tactic: 0x00000000000203ae numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000203ae Time: 0.324315 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize256x128x32_stage3_warpsize4x2x1_tensor16x8x16 Tactic: 0x00000000000203af numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000203af Time: 0.356983 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x128x32_stage4_warpsize2x2x1_tensor16x8x16 Tactic: 0x0000000000020416 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020416 Time: 0.356206 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x256_ldg8_relu_nn_v1 Tactic: 0x000000000002041d numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002041d Time: 0.320663 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x64x64_stage3_warpsize2x2x1_tensor16x8x16 Tactic: 0x0000000000020462 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020462 Time: 0.483424 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_ldg8_relu_nn_v1 Tactic: 0x000000000002047b numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002047b Time: 0.324754 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x64_ldg8_relu_nn_v1 Tactic: 0x000000000002048a numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002048a Time: 0.350501 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x128_ldg8_stages_32x3_nn_v1 Tactic: 0x00000000000204ca numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000204ca Time: 0.399945 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize256x64x32_stage3_warpsize4x1x1_tensor16x8x16 Tactic: 0x00000000000204ce numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000204ce Time: 0.472503 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm86_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize256x128x32_stage2_warpsize4x2x1_tensor16x8x16 Tactic: 0x00000000000204df numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000204df Time: 0.401408 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_stages_64x4_nn_v1 Tactic: 0x00000000000204f0 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000204f0 Time: 0.359863 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_sliced1x2_ldg8_relu_nn_v1 Tactic: 0x0000000000020032 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020032 Time: 0.318903 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize64x32x64_stage5_warpsize2x2x1_tensor16x8x16 Tactic: 0x0000000000020540 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020540 Time: 0.733915 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_nn_v1 Tactic: 0x00000000000205a1 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000205a1 Time: 0.32256 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_relu_stages_32x6_nn_v1 Tactic: 0x00000000000205b3 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000205b3 Time: 0.350208 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x256_ldg8_nn_v1 Tactic: 0x00000000000205f1 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000205f1 Time: 0.4096 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x128_ldg8_relu_stages_32x6_nn_v1 Tactic: 0x0000000000020608 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020608 Time: 0.369664 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_relu_nn_v1 Tactic: 0x00000000000206b5 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000206b5 Time: 0.290565 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x128_ldg8_relu_stages_32x3_nn_v1 Tactic: 0x00000000000206b8 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000206b8 Time: 0.317733 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_sliced1x2_ldg8_stages_64x5_nn_v1 Tactic: 0x00000000000206cb numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000206cb Time: 0.435054 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_stages_32x5_nn_v1 Tactic: 0x0000000000020700 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020700 Time: 0.308809 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_stages_32x6_nn_v1 Tactic: 0x0000000000020718 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020718 Time: 0.400238 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x64_ldg8_nn_v1 Tactic: 0x000000000002072e numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002072e Time: 0.336777 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_sliced1x2_ldg8_relu_stages_64x5_nn_v1 Tactic: 0x00000000000202ea numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000202ea Time: 0.457874 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_ldg8_nn_v1 Tactic: 0x0000000000020153 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020153 Time: 0.39936 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_sliced1x2_ldg8_relu_nn_v1 Tactic: 0x00000000000201b7 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000201b7 Time: 0.334555 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_ldg8_relu_stages_64x5_nn_v1 Tactic: 0x0000000000020146 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020146 Time: 0.438565 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x128_ldg8_relu_stages_64x4_nn_v1 Tactic: 0x00000000000201cc numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000201cc Time: 0.445733 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x128_ldg8_nn_v1 Tactic: 0x0000000000020101 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020101 Time: 0.320658 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_relu_stages_64x4_nn_v1 Tactic: 0x000000000002027b numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002027b Time: 0.369829 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_nn_v1 Tactic: 0x00000000000200fb numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000200fb Time: 0.287598 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_relu_stages_32x5_nn_v1 Tactic: 0x00000000000202e5 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000202e5 Time: 0.323918 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x128_ldg8_stages_64x4_nn_v1 Tactic: 0x00000000000200ee numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000200ee Time: 0.375662 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_relu_nn_v1 Tactic: 0x00000000000200b6 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000200b6 Time: 0.446903 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize32x32x64_stage6_warpsize2x2x1_tensor16x8x16 Tactic: 0x00000000000202fd numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000202fd Time: 0.723822 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_sliced1x2_ldg8_nn_v1 Tactic: 0x00000000000200a4 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000200a4 Time: 0.329289 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize64x128x32_stage5_warpsize2x2x1_tensor16x8x16 Tactic: 0x000000000002031c numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002031c Time: 0.410226 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_sliced1x2_ldg8_nn_v1 Tactic: 0x000000000002007b numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002007b Time: 0.317879 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize64x64x64_stage4_warpsize2x2x1_tensor16x8x16 Tactic: 0x000000000002032f numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002032f Time: 0.475429 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x128_ldg8_stages_32x6_nn_v1 Tactic: 0x000000000002005b numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000002005b Time: 0.47499 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x256x32_stage3_warpsize2x4x1_tensor16x8x16 Tactic: 0x0000000000020355 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020355 Time: 0.317294 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_ldg8_stages_64x5_nn_v1 Tactic: 0x0000000000020009 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000000020009 Time: 0.438418 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x64x32_stage5_warpsize2x2x1_tensor16x8x16 Tactic: 0x00000000000203ad numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000000203ad Time: 0.535552 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x64_ldg8_nn_v1 Tactic: 0x000000000204072e numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000204072e Time: 0.469307 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize256x64x32_stage3_warpsize4x1x1_tensor16x8x16 Tactic: 0x00000000020404ce numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000020404ce Time: 1.00466 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x64_ldg8_relu_nn_v1 Tactic: 0x000000000204048a numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x000000000204048a Time: 0.480987 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x128x64_stage3_warpsize2x2x1_tensor16x8x16 Tactic: 0x00000000020404f2 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000020404f2 Time: 0.683739 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_nn_v1 Tactic: 0x00000000020405a1 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000020405a1 Time: 0.447927 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_stages_32x5_nn_v1 Tactic: 0x0000000002040700 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x0000000002040700 Time: 0.457289 +[03/18/2024-15:13:07] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_relu_nn_v1 Tactic: 0x00000000020400b6 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:07] [V] [TRT] Tactic: 0x00000000020400b6 Time: 0.4608 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_relu_stages_32x5_nn_v1 Tactic: 0x00000000020402e5 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000020402e5 Time: 0.465486 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x128x32_stage4_warpsize2x2x1_tensor16x8x16 Tactic: 0x0000000002040416 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000002040416 Time: 0.613815 +[03/18/2024-15:13:08] [V] [TRT] Fastest Tactic: 0x00000000000200fb Time: 0.287598 +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_strided Tactic: 0xdec24e75875e331b +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xdec24e75875e331b Time: 0.165006 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_strided Tactic: 0xa7e51cc94b1422a2 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xa7e51cc94b1422a2 Time: 0.217998 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0x3d8e7318766eb7dc +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x3d8e7318766eb7dc Time: 0.172763 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x86e575ac0953a218 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x86e575ac0953a218 Time: 0.429495 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x93d63ec59e26a994 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x93d63ec59e26a994 Time: 0.464759 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x350fa92a3841d3f8 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x350fa92a3841d3f8 Time: 0.640585 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0xbe1fd751d1abb95e +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xbe1fd751d1abb95e Time: 0.479232 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x7bb6e0d53fc5ff66 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x7bb6e0d53fc5ff66 Time: 0.493714 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xad900cb3d99acf3d +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xad900cb3d99acf3d Time: 0.46709 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x9e7119e6665ed23e +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x9e7119e6665ed23e Time: 0.832503 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xff74b048c704a0c3 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xff74b048c704a0c3 Time: 0.433591 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0x7f88a42f41dd3253 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x7f88a42f41dd3253 Time: 0.329582 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0xd8431473bb5f91ee +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xd8431473bb5f91ee Time: 0.227913 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0x611e899dccd3003a +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x611e899dccd3003a Time: 0.183296 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_strided Tactic: 0x9c2afe40f043a2af +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x9c2afe40f043a2af Time: 0.199095 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0x7cc22b876c6d2b93 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x7cc22b876c6d2b93 Time: 0.231278 +[03/18/2024-15:13:08] [V] [TRT] Fastest Tactic: 0xdec24e75875e331b Time: 0.165006 +[03/18/2024-15:13:08] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskDeconvolutionV2 Tactic: 0xdec24e75875e331b +[03/18/2024-15:13:08] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,2880,32) -> Half(1036800,1:8,5760,32) *************** +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.330167 +[03/18/2024-15:13:08] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.330167 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58: 62 available tactics, 44 unparsable, 9 pruned, 53 remaining after tactic pruning. +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskGemmDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x128x64_stage3_warpsize2x2x1_tensor16x8x16 Tactic: 0x00000000000204f2 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000204f2 Time: 0.361326 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x128_ldg8_relu_nn_v1 Tactic: 0x00000000000203ae numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000203ae Time: 0.332507 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize256x128x32_stage3_warpsize4x2x1_tensor16x8x16 Tactic: 0x00000000000203af numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000203af Time: 0.35957 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x128x32_stage4_warpsize2x2x1_tensor16x8x16 Tactic: 0x0000000000020416 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020416 Time: 0.496777 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x256_ldg8_relu_nn_v1 Tactic: 0x000000000002041d numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000002041d Time: 0.335287 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x64x64_stage3_warpsize2x2x1_tensor16x8x16 Tactic: 0x0000000000020462 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020462 Time: 0.473381 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_ldg8_relu_nn_v1 Tactic: 0x000000000002047b numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000002047b Time: 0.330167 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x64_ldg8_relu_nn_v1 Tactic: 0x000000000002048a numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000002048a Time: 0.409463 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x128_ldg8_stages_32x3_nn_v1 Tactic: 0x00000000000204ca numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000204ca Time: 0.315831 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize256x64x32_stage3_warpsize4x1x1_tensor16x8x16 Tactic: 0x00000000000204ce numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000204ce Time: 0.470894 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm86_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize256x128x32_stage2_warpsize4x2x1_tensor16x8x16 Tactic: 0x00000000000204df numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000204df Time: 0.511269 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_stages_64x4_nn_v1 Tactic: 0x00000000000204f0 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000204f0 Time: 0.364398 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_sliced1x2_ldg8_relu_nn_v1 Tactic: 0x0000000000020032 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020032 Time: 0.319931 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize64x32x64_stage5_warpsize2x2x1_tensor16x8x16 Tactic: 0x0000000000020540 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020540 Time: 0.784091 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_nn_v1 Tactic: 0x00000000000205a1 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000205a1 Time: 0.327095 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_relu_stages_32x6_nn_v1 Tactic: 0x00000000000205b3 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000205b3 Time: 0.419255 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x256_ldg8_nn_v1 Tactic: 0x00000000000205f1 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000205f1 Time: 0.33163 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x128_ldg8_relu_stages_32x6_nn_v1 Tactic: 0x0000000000020608 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020608 Time: 0.376832 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_relu_nn_v1 Tactic: 0x00000000000206b5 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000206b5 Time: 0.288475 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x128_ldg8_relu_stages_32x3_nn_v1 Tactic: 0x00000000000206b8 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000206b8 Time: 0.317879 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_sliced1x2_ldg8_stages_64x5_nn_v1 Tactic: 0x00000000000206cb numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000206cb Time: 0.439003 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_stages_32x5_nn_v1 Tactic: 0x0000000000020700 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020700 Time: 0.376978 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_stages_32x6_nn_v1 Tactic: 0x0000000000020718 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020718 Time: 0.341138 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x64_ldg8_nn_v1 Tactic: 0x000000000002072e numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000002072e Time: 0.337774 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_sliced1x2_ldg8_relu_stages_64x5_nn_v1 Tactic: 0x00000000000202ea numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000202ea Time: 0.563054 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_ldg8_nn_v1 Tactic: 0x0000000000020153 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020153 Time: 0.314514 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_sliced1x2_ldg8_relu_nn_v1 Tactic: 0x00000000000201b7 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000201b7 Time: 0.337042 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_ldg8_relu_stages_64x5_nn_v1 Tactic: 0x0000000000020146 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020146 Time: 0.442514 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x128_ldg8_relu_stages_64x4_nn_v1 Tactic: 0x00000000000201cc numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000201cc Time: 0.43915 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x128_ldg8_nn_v1 Tactic: 0x0000000000020101 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020101 Time: 0.32384 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_relu_stages_64x4_nn_v1 Tactic: 0x000000000002027b numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000002027b Time: 0.37888 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_ldg8_nn_v1 Tactic: 0x00000000000200fb numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000200fb Time: 0.289353 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_relu_stages_32x5_nn_v1 Tactic: 0x00000000000202e5 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000202e5 Time: 0.331191 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x128_ldg8_stages_64x4_nn_v1 Tactic: 0x00000000000200ee numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000200ee Time: 0.382537 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_relu_nn_v1 Tactic: 0x00000000000200b6 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000200b6 Time: 0.342715 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize32x32x64_stage6_warpsize2x2x1_tensor16x8x16 Tactic: 0x00000000000202fd numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000202fd Time: 0.725696 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_sliced1x2_ldg8_nn_v1 Tactic: 0x00000000000200a4 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000200a4 Time: 0.335726 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize64x128x32_stage5_warpsize2x2x1_tensor16x8x16 Tactic: 0x000000000002031c numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000002031c Time: 0.464311 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x64_sliced1x2_ldg8_nn_v1 Tactic: 0x000000000002007b numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000002007b Time: 0.318162 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize64x64x64_stage4_warpsize2x2x1_tensor16x8x16 Tactic: 0x000000000002032f numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000002032f Time: 0.474405 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x128_ldg8_stages_32x6_nn_v1 Tactic: 0x000000000002005b numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000002005b Time: 0.482597 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x256x32_stage3_warpsize2x4x1_tensor16x8x16 Tactic: 0x0000000000020355 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020355 Time: 0.317733 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_64x64_ldg8_stages_64x5_nn_v1 Tactic: 0x0000000000020009 numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000000020009 Time: 0.439735 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x64x32_stage5_warpsize2x2x1_tensor16x8x16 Tactic: 0x00000000000203ad numSplitK: 1 numBuffers: 0 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000203ad Time: 0.473819 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x64_ldg8_nn_v1 Tactic: 0x000000000204072e numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000204072e Time: 0.466651 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize256x64x32_stage3_warpsize4x1x1_tensor16x8x16 Tactic: 0x00000000020404ce numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000020404ce Time: 0.986697 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_256x64_ldg8_relu_nn_v1 Tactic: 0x000000000204048a numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000204048a Time: 0.479086 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x128x64_stage3_warpsize2x2x1_tensor16x8x16 Tactic: 0x00000000020404f2 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000020404f2 Time: 0.670455 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_nn_v1 Tactic: 0x00000000020405a1 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000020405a1 Time: 0.448366 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_stages_32x5_nn_v1 Tactic: 0x0000000002040700 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000002040700 Time: 0.455095 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_relu_nn_v1 Tactic: 0x00000000020400b6 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000020400b6 Time: 0.45685 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: ampere_h16816gemm_128x128_ldg8_relu_stages_32x5_nn_v1 Tactic: 0x00000000020402e5 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000020402e5 Time: 0.461824 +[03/18/2024-15:13:08] [V] [TRT] Set Tactic Name: sm80_xmma_gemm_f16f16_f16f16_f16_nn_n_tilesize128x128x32_stage4_warpsize2x2x1_tensor16x8x16 Tactic: 0x0000000002040416 numSplitK: 2 numBuffers: 1 numKernels: 1 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x0000000002040416 Time: 0.610011 +[03/18/2024-15:13:08] [V] [TRT] Fastest Tactic: 0x00000000000206b5 Time: 0.288475 +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_strided Tactic: 0xdec24e75875e331b +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xdec24e75875e331b Time: 0.164864 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_strided Tactic: 0xa7e51cc94b1422a2 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xa7e51cc94b1422a2 Time: 0.220059 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0x3d8e7318766eb7dc +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x3d8e7318766eb7dc Time: 0.173934 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x86e575ac0953a218 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x86e575ac0953a218 Time: 0.43125 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x93d63ec59e26a994 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x93d63ec59e26a994 Time: 0.477787 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x350fa92a3841d3f8 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x350fa92a3841d3f8 Time: 0.545499 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0xbe1fd751d1abb95e +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xbe1fd751d1abb95e Time: 0.495762 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x7bb6e0d53fc5ff66 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x7bb6e0d53fc5ff66 Time: 0.515666 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xad900cb3d99acf3d +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xad900cb3d99acf3d Time: 0.477915 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x9e7119e6665ed23e +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x9e7119e6665ed23e Time: 0.975433 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xff74b048c704a0c3 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xff74b048c704a0c3 Time: 0.509952 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0x7f88a42f41dd3253 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x7f88a42f41dd3253 Time: 0.351671 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0xd8431473bb5f91ee +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0xd8431473bb5f91ee Time: 0.24459 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0x611e899dccd3003a +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x611e899dccd3003a Time: 0.196169 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_strided Tactic: 0x9c2afe40f043a2af +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x9c2afe40f043a2af Time: 0.201289 +[03/18/2024-15:13:08] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_strided Tactic: 0x7cc22b876c6d2b93 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x7cc22b876c6d2b93 Time: 0.233765 +[03/18/2024-15:13:08] [V] [TRT] Fastest Tactic: 0xdec24e75875e331b Time: 0.164864 +[03/18/2024-15:13:08] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskDeconvolutionV2 Tactic: 0xdec24e75875e331b +[03/18/2024-15:13:08] [V] [TRT] *************** Autotuning format combination: Half(129600,1:16,1440,16) -> Half(1036800,1:16,5760,32) long-strided *************** +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] GemmDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:08] [V] [TRT] CaskDeconvolutionV2 has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] *************** Autotuning format combination: Half(129600,1:16,1440,16) -> Half(518400,1:16,2880,16) *************** +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CudnnDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] CudnnDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (GemmDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] GemmDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolution) +[03/18/2024-15:13:08] [V] [TRT] CaskDeconvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: ConvTranspose_56 + BatchNormalization_57 + Relu_58 (CaskDeconvolutionV2) +[03/18/2024-15:13:08] [V] [TRT] CaskDeconvolutionV2 has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:08] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CudaDepthwiseConvolution) +[03/18/2024-15:13:08] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:08] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (FusedConvActConvolution) +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000007ffff Time: 3.02095 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000affff Time: 4.1384 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000effff Time: 4.52272 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000000fffff Time: 5.08709 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000019ffff Time: 4.7006 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000001affff Time: 4.98776 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000024ffff Time: 4.84879 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000027ffff Time: 4.00867 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000002dffff Time: 3.93435 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000036ffff Time: 4.06835 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000004cffff Time: 3.80928 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x000000000062ffff Time: 4.26496 +[03/18/2024-15:13:08] [V] [TRT] Tactic: 0x00000000006effff Time: 4.49229 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x000000000077ffff Time: 4.18582 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x000000000086ffff Time: 4.74814 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x000000000089ffff Time: 3.62423 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x000000000097ffff Time: 4.82028 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x000000000098ffff Time: 3.69386 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x00000000009fffff Time: 3.52431 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x0000000000a2ffff Time: 4.69358 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x0000000000a4ffff Time: 4.15495 +[03/18/2024-15:13:09] [V] [TRT] Fastest Tactic: 0x000000000007ffff Time: 3.02095 +[03/18/2024-15:13:09] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CudnnConvolution) +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x0000000000000000 Time: 8.66026 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x0000000000000001 Time: 3.03616 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x0000000000000002 Time: 10.9967 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x0000000000000005 Time: 22.9124 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x0000000000000006 Time: 2.37246 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x0000000000000038 Time: 8.98633 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x0000000000000039 Time: 3.08486 +[03/18/2024-15:13:09] [V] [TRT] Tactic: 0x000000000000003a Time: 11.159 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x000000000000003d Time: 22.9231 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x000000000000003e Time: 2.44196 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x0000000000000070 Time: 8.97624 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x0000000000000071 Time: 4.06543 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x0000000000000072 Time: 11.9075 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x0000000000000075 Time: 22.8384 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x0000000000000076 Time: 2.4418 +[03/18/2024-15:13:10] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 2.37246 +[03/18/2024-15:13:10] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskGemmConvolution) +[03/18/2024-15:13:10] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:10] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskFlattenConvolution) +[03/18/2024-15:13:10] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:10] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskConvolution) +[03/18/2024-15:13:10] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 4.49799 +[03/18/2024-15:13:10] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 3.94737 +[03/18/2024-15:13:10] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 4.21274 +[03/18/2024-15:13:10] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 2.41298 +[03/18/2024-15:13:10] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 7.37134 +[03/18/2024-15:13:10] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 6.87616 +[03/18/2024-15:13:10] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 7.62192 +[03/18/2024-15:13:10] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 11.6985 +[03/18/2024-15:13:10] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:10] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 6.69989 +[03/18/2024-15:13:10] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 5.43552 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 4.06104 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 6.69506 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 6.38991 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x4727434768e46395 Time: 4.60054 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 7.38143 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 6.65585 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 5.70939 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 4.41666 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 4.23322 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 6.57627 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 7.12631 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 6.3981 +[03/18/2024-15:13:11] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 2.41298 +[03/18/2024-15:13:11] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000006 +[03/18/2024-15:13:11] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) -> Float(2073600,1,11520,64) *************** +[03/18/2024-15:13:11] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskFlattenConvolution) +[03/18/2024-15:13:11] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:11] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskConvolution) +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x27b316f52c109002 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x27b316f52c109002 Time: 3.27358 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x128_relu_exp_medium_nhwc_tn_v1 Tactic: 0xd9031472c05adf51 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0xd9031472c05adf51 Time: 6.83067 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x3e2b881168d9689d +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x3e2b881168d9689d Time: 3.87408 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0xf90060ce8193b811 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0xf90060ce8193b811 Time: 6.66229 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0xbdfdef6b84f7ccc9 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0xbdfdef6b84f7ccc9 Time: 3.59877 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x412c44dfeaf9161d +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x412c44dfeaf9161d Time: 4.03953 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x7bc32c782b800c48 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x7bc32c782b800c48 Time: 6.3311 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 6.00518 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:11] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 4.13038 +[03/18/2024-15:13:11] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 5.29876 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 3.5464 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x3e191488237fab8f +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x3e191488237fab8f Time: 4.18611 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 7.58826 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 7.16595 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 11.8048 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 7.8671 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 4.01613 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 4.24185 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x128_relu_exp_large_nhwc_tn_v1 Tactic: 0xca7eeb8d9143d738 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0xca7eeb8d9143d738 Time: 6.89942 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 4.09995 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 3.53367 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x128_relu_exp_small_nhwc_tn_v1 Tactic: 0x5030121339a48bf3 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x5030121339a48bf3 Time: 7.17736 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 6.0397 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 6.21599 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 6.43584 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0x634e99502974e4da +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x634e99502974e4da Time: 6.92385 +[03/18/2024-15:13:12] [V] [TRT] Fastest Tactic: 0x27b316f52c109002 Time: 3.27358 +[03/18/2024-15:13:12] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x27b316f52c109002 +[03/18/2024-15:13:12] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) -> Float(518400,1:4,2880,16) *************** +[03/18/2024-15:13:12] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CudaDepthwiseConvolution) +[03/18/2024-15:13:12] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:12] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskGemmConvolution) +[03/18/2024-15:13:12] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:12] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskFlattenConvolution) +[03/18/2024-15:13:12] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:12] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskConvolution) +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 3.97283 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 3.88319 +[03/18/2024-15:13:12] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:12] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 3.55328 +[03/18/2024-15:13:12] [V] [TRT] Fastest Tactic: 0xb443c221fcb1565b Time: 3.55328 +[03/18/2024-15:13:12] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:12] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) -> Half(2073600,32400,180,1) *************** +[03/18/2024-15:13:12] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CudnnConvolution) +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x0000000000000000 Time: 6.99904 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x0000000000000001 Time: 4.65291 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x0000000000000002 Time: 9.83991 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x0000000000000005 Time: 22.5448 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x0000000000000006 Time: 3.07624 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x0000000000000038 Time: 8.8794 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x000000000000003a Time: 9.69494 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x000000000000003d Time: 22.3279 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x000000000000003e Time: 2.91884 +[03/18/2024-15:13:13] [V] [TRT] Fastest Tactic: 0x000000000000003e Time: 2.91884 +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskGemmConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskFlattenConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x000000000000003e +[03/18/2024-15:13:13] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) -> Half(1036800,32400:2,180,1) *************** +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (FusedConvActConvolution) +[03/18/2024-15:13:13] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskFlattenConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) -> Half(518400,1:4,2880,16) *************** +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskFlattenConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) -> Float(2073600,32400,180,1) *************** +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskFlattenConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) -> Half(259200,1:8,1440,8) *************** +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CudaDepthwiseConvolution) +[03/18/2024-15:13:13] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskGemmConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskFlattenConvolution) +[03/18/2024-15:13:13] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:13] [V] [TRT] --------------- Timing Runner: Conv_60 + Relu_61 (CaskConvolution) +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.527067 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.53365 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 1.08924 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.639712 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 1.18828 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.645705 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 1.08325 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.925257 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 1.24987 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.679515 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.936951 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 1.15489 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 1.10414 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 1.20715 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.582802 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.947785 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.994011 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 1.07666 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.567881 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 1.07593 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.549595 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.828416 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.545646 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.655214 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.612937 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.5632 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.562469 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 1.14274 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 1.25165 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:13] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 1.15712 +[03/18/2024-15:13:13] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.549595 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.64629 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.651849 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.982162 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.797403 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.520777 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.561737 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.726853 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.530286 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.638098 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.754834 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.793161 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 1.17014 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.957303 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.898926 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.674272 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 1.95189 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.679497 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.514926 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.530578 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.697051 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 1.14044 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.944713 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.692361 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.757202 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.94091 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.980261 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 1.23084 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 1.13225 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.497079 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 1.01903 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 1.10972 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 1.04843 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.660919 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.770926 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.719287 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.640859 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.976603 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 1.04433 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.745911 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.629029 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.905362 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.776046 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 2.04727 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 1.1214 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.936375 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.544914 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.67749 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.541403 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.546057 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.851675 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.97307 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 1.16326 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.624494 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.655506 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.92043 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.584663 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 1.16312 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.694711 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 1.01259 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 2.09393 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.613669 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.96885 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 1.27649 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.965632 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 1.00791 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.761125 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 1.04594 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.592896 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.73387 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 1.02517 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 1.09831 +[03/18/2024-15:13:14] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.642341 +[03/18/2024-15:13:14] [V] [TRT] Fastest Tactic: 0xb4bec086187edcfc Time: 0.497079 +[03/18/2024-15:13:14] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:14] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:14] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:13:14] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CudaDepthwiseConvolution) +[03/18/2024-15:13:14] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:14] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (FusedConvActConvolution) +[03/18/2024-15:13:14] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:14] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CudnnConvolution) +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x0000000000000000 Time: 5.32348 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x0000000000000001 Time: 3.92455 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x0000000000000002 Time: 6.11518 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x0000000000000005 Time: 23.7199 +[03/18/2024-15:13:14] [V] [TRT] Tactic: 0x0000000000000006 Time: 4.17924 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x0000000000000038 Time: 6.01749 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x0000000000000039 Time: 3.58093 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x000000000000003a Time: 5.66023 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x000000000000003d Time: 23.9477 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x000000000000003e Time: 4.05972 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x0000000000000070 Time: 5.91916 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x0000000000000071 Time: 4.92003 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x0000000000000072 Time: 5.9256 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x0000000000000075 Time: 24.1445 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x0000000000000076 Time: 3.77125 +[03/18/2024-15:13:15] [V] [TRT] Fastest Tactic: 0x0000000000000039 Time: 3.58093 +[03/18/2024-15:13:15] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskGemmConvolution) +[03/18/2024-15:13:15] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:15] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskFlattenConvolution) +[03/18/2024-15:13:15] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:15] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskConvolution) +[03/18/2024-15:13:15] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 4.58503 +[03/18/2024-15:13:15] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 3.90949 +[03/18/2024-15:13:15] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 3.91402 +[03/18/2024-15:13:15] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 2.78174 +[03/18/2024-15:13:15] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 4.09659 +[03/18/2024-15:13:15] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 4.08664 +[03/18/2024-15:13:15] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:15] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 8.39651 +[03/18/2024-15:13:15] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 11.5082 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 3.41343 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 6.03312 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 4.212 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 7.63042 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 5.78765 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x4727434768e46395 Time: 4.69914 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 3.79246 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 3.49374 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 6.35246 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 3.94971 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 4.1175 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 3.55899 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 7.46553 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 3.46785 +[03/18/2024-15:13:16] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 2.78174 +[03/18/2024-15:13:16] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:16] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:13:16] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskFlattenConvolution) +[03/18/2024-15:13:16] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:16] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskConvolution) +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x27b316f52c109002 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x27b316f52c109002 Time: 3.11208 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x128_relu_exp_medium_nhwc_tn_v1 Tactic: 0xd9031472c05adf51 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0xd9031472c05adf51 Time: 3.50544 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x3e2b881168d9689d +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x3e2b881168d9689d Time: 4.17792 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0xf90060ce8193b811 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0xf90060ce8193b811 Time: 3.53485 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0xbdfdef6b84f7ccc9 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0xbdfdef6b84f7ccc9 Time: 3.77051 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x412c44dfeaf9161d +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x412c44dfeaf9161d Time: 3.9074 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x7bc32c782b800c48 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x7bc32c782b800c48 Time: 3.38988 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 6.69447 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:16] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 4.39033 +[03/18/2024-15:13:16] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 5.33255 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 3.49872 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x3e191488237fab8f +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x3e191488237fab8f Time: 4.43479 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 7.21919 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 7.04132 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 4.1254 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 7.94446 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 4.14893 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 3.37408 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x128_relu_exp_large_nhwc_tn_v1 Tactic: 0xca7eeb8d9143d738 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0xca7eeb8d9143d738 Time: 3.6055 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 4.38667 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 3.66972 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x128_relu_exp_small_nhwc_tn_v1 Tactic: 0x5030121339a48bf3 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x5030121339a48bf3 Time: 3.60697 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 6.9335 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 3.51408 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 6.50138 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0x634e99502974e4da +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x634e99502974e4da Time: 3.60975 +[03/18/2024-15:13:17] [V] [TRT] Fastest Tactic: 0x27b316f52c109002 Time: 3.11208 +[03/18/2024-15:13:17] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x27b316f52c109002 +[03/18/2024-15:13:17] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:13:17] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CudaDepthwiseConvolution) +[03/18/2024-15:13:17] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:17] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskGemmConvolution) +[03/18/2024-15:13:17] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:17] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskFlattenConvolution) +[03/18/2024-15:13:17] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:17] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskConvolution) +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 2.22076 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 2.25353 +[03/18/2024-15:13:17] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 1.98364 +[03/18/2024-15:13:17] [V] [TRT] Fastest Tactic: 0xb443c221fcb1565b Time: 1.98364 +[03/18/2024-15:13:17] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:17] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:13:17] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CudnnConvolution) +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x0000000000000000 Time: 6.42281 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x0000000000000001 Time: 7.17224 +[03/18/2024-15:13:17] [V] [TRT] Tactic: 0x0000000000000002 Time: 5.49581 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x0000000000000005 Time: 23.56 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x0000000000000006 Time: 4.19753 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x0000000000000038 Time: 7.47023 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x000000000000003a Time: 5.31295 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x000000000000003d Time: 23.5026 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x000000000000003e Time: 4.26862 +[03/18/2024-15:13:18] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 4.19753 +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskGemmConvolution) +[03/18/2024-15:13:18] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskFlattenConvolution) +[03/18/2024-15:13:18] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskConvolution) +[03/18/2024-15:13:18] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000006 +[03/18/2024-15:13:18] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (FusedConvActConvolution) +[03/18/2024-15:13:18] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskFlattenConvolution) +[03/18/2024-15:13:18] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskConvolution) +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_small_nn_v1 Tactic: 0xea8b68014eaeb55d +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xea8b68014eaeb55d Time: 2.0521 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_medium_nn_v1 Tactic: 0x1e7896ba71ef1635 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x1e7896ba71ef1635 Time: 1.89586 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_fp16x2_hcudnn_winograd_fp16x2_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xc754debea88ae0b7 Time: 1.47851 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_large_nn_v1 Tactic: 0x91f7e9c0851ad67c +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x91f7e9c0851ad67c Time: 2.29478 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_medium_nn_v1 Tactic: 0x360278e347d63410 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x360278e347d63410 Time: 2.3394 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_small_nn_v1 Tactic: 0xc34b78af38b295a7 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xc34b78af38b295a7 Time: 2.18463 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_large_nn_v1 Tactic: 0xb837f96ef306f686 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xb837f96ef306f686 Time: 2.30078 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_medium_nn_v1 Tactic: 0x4cfee77ea8c324db +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x4cfee77ea8c324db Time: 2.06672 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_large_nn_v1 Tactic: 0x2f735ffbb05a30fd +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x2f735ffbb05a30fd Time: 2.44982 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_small_nn_v1 Tactic: 0x540fde3a7bee53dc +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x540fde3a7bee53dc Time: 2.17483 +[03/18/2024-15:13:18] [V] [TRT] Fastest Tactic: 0xc754debea88ae0b7 Time: 1.47851 +[03/18/2024-15:13:18] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:18] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskFlattenConvolution) +[03/18/2024-15:13:18] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskConvolution) +[03/18/2024-15:13:18] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskFlattenConvolution) +[03/18/2024-15:13:18] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskConvolution) +[03/18/2024-15:13:18] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CudaDepthwiseConvolution) +[03/18/2024-15:13:18] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskGemmConvolution) +[03/18/2024-15:13:18] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskFlattenConvolution) +[03/18/2024-15:13:18] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:18] [V] [TRT] --------------- Timing Runner: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (CaskConvolution) +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 1.06847 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.754542 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.72939 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.631077 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.495762 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.742839 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.774729 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.723374 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.620251 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.867474 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.973531 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.72075 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.770341 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.746642 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 1.29741 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.715483 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.702025 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.752494 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.971776 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.765513 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 1.14044 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.544914 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.820809 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.84875 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 1.02254 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 1.00235 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.837925 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.632832 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.759515 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.666185 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.897902 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.799305 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.848329 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.625664 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.895269 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.809106 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 1.09056 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.95232 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 1.03965 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.797842 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.785847 +[03/18/2024-15:13:18] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:18] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.779264 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.624238 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.711534 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.911653 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.946021 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.611602 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.845531 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.905655 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.756297 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.586459 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.667502 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.585289 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.72192 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.752073 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.509952 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 1.80838 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.653925 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.563086 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.742546 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.735963 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.774437 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.840558 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.699099 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.9216 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.87552 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.634295 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.86923 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.647461 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.576073 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.599771 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 1.08705 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.952466 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.671451 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.727771 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.640585 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 1.20393 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x6af049035146c349 Time: 1.0654 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.661797 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.744009 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 1.06352 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.834706 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.655945 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.824466 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.944274 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.738629 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.848311 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.697344 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 1.05706 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.613522 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.759369 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.598747 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.735671 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.613815 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.601234 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.623936 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.94208 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 1.69282 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 1.06759 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.734501 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 1.55984 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.703621 +[03/18/2024-15:13:19] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.734354 +[03/18/2024-15:13:19] [V] [TRT] Fastest Tactic: 0xa927df92ac1ef1b8 Time: 0.495762 +[03/18/2024-15:13:19] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:19] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:19] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CudaDepthwiseConvolution) +[03/18/2024-15:13:19] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (FusedConvActConvolution) +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000007ffff Time: 0.202752 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x00000000000affff Time: 0.341577 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x00000000000effff Time: 0.362496 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x00000000000fffff Time: 0.197047 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000019ffff Time: 0.19573 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x00000000001affff Time: 0.440027 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000024ffff Time: 0.370542 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000027ffff Time: 0.220891 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x00000000002dffff Time: 0.209481 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000036ffff Time: 0.215918 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x00000000004cffff Time: 0.212261 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000062ffff Time: 0.203337 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x00000000006effff Time: 0.503808 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000077ffff Time: 0.218112 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000086ffff Time: 0.302373 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000089ffff Time: 0.202313 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000097ffff Time: 0.284672 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000098ffff Time: 0.208311 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x00000000009fffff Time: 0.206409 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000a2ffff Time: 0.22133 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000a4ffff Time: 0.415598 +[03/18/2024-15:13:19] [V] [TRT] Fastest Tactic: 0x000000000019ffff Time: 0.19573 +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CudnnConvolution) +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.339822 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.349915 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.369225 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.22397 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.450414 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.138386 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.283355 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000039 Time: 0.332361 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000000003a Time: 0.396142 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000000003c Time: 1.40332 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000000003d Time: 0.398331 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000000003e Time: 0.136631 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000070 Time: 0.279845 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000071 Time: 0.379904 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000072 Time: 0.277504 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000074 Time: 1.46432 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000075 Time: 0.397134 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000076 Time: 0.136411 +[03/18/2024-15:13:19] [V] [TRT] Fastest Tactic: 0x0000000000000076 Time: 0.136411 +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskGemmConvolution) +[03/18/2024-15:13:19] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:19] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 0.242103 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 0.345563 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.366007 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 0.127634 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.624078 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 0.764928 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 0.434176 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 0.30661 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 0.757029 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 0.574464 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.398514 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 0.182272 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 0.342455 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x4727434768e46395 Time: 0.470455 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 0.744594 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 0.841435 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 0.416475 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.419109 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 0.55808 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 0.838949 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 0.433737 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.770194 +[03/18/2024-15:13:19] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 0.127634 +[03/18/2024-15:13:19] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:19] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:19] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 0.282039 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 0.475867 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 0.260681 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.324315 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 0.318171 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 0.190153 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 1.4039 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 0.209189 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.362057 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.51712 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 0.432128 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 0.436224 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 0.372297 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 0.636635 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 0.179931 +[03/18/2024-15:13:19] [V] [TRT] Fastest Tactic: 0x92ed3100c35fc43e Time: 0.179931 +[03/18/2024-15:13:19] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:19] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CudaDepthwiseConvolution) +[03/18/2024-15:13:19] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskGemmConvolution) +[03/18/2024-15:13:19] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:19] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 0.503808 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.497664 +[03/18/2024-15:13:19] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.476014 +[03/18/2024-15:13:19] [V] [TRT] Fastest Tactic: 0xb443c221fcb1565b Time: 0.476014 +[03/18/2024-15:13:19] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:19] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CudnnConvolution) +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.284672 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.342455 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.284672 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.28512 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.618496 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000006 Time: 2.31365 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.367616 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000000003a Time: 0.294034 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000000003c Time: 1.3195 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000000003d Time: 0.534089 +[03/18/2024-15:13:19] [V] [TRT] Tactic: 0x000000000000003e Time: 2.14879 +[03/18/2024-15:13:19] [V] [TRT] Fastest Tactic: 0x0000000000000000 Time: 0.284672 +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskGemmConvolution) +[03/18/2024-15:13:19] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:19] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:19] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000000 +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (FusedConvActConvolution) +[03/18/2024-15:13:20] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_small_nn_v1 Tactic: 0xea8b68014eaeb55d +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xea8b68014eaeb55d Time: 0.552375 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_medium_nn_v1 Tactic: 0x1e7896ba71ef1635 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x1e7896ba71ef1635 Time: 0.135022 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_winograd_fp16x2_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc754debea88ae0b7 Time: 0.0776046 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_large_nn_v1 Tactic: 0x91f7e9c0851ad67c +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x91f7e9c0851ad67c Time: 0.463287 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_medium_nn_v1 Tactic: 0x360278e347d63410 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x360278e347d63410 Time: 0.502638 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_small_nn_v1 Tactic: 0xc34b78af38b295a7 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc34b78af38b295a7 Time: 0.124926 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_large_nn_v1 Tactic: 0xb837f96ef306f686 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb837f96ef306f686 Time: 0.127271 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_medium_nn_v1 Tactic: 0x4cfee77ea8c324db +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x4cfee77ea8c324db Time: 0.211237 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_large_nn_v1 Tactic: 0x2f735ffbb05a30fd +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x2f735ffbb05a30fd Time: 0.212553 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_small_nn_v1 Tactic: 0x540fde3a7bee53dc +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x540fde3a7bee53dc Time: 0.20875 +[03/18/2024-15:13:20] [V] [TRT] Fastest Tactic: 0xc754debea88ae0b7 Time: 0.0776046 +[03/18/2024-15:13:20] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CudaDepthwiseConvolution) +[03/18/2024-15:13:20] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskGemmConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.115346 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.0922331 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.164256 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.0945006 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.120706 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.0896731 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.138606 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.136923 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.136117 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.0864549 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.157989 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.139927 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.138167 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.129097 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.111909 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.136923 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.128658 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.150235 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.098816 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.130121 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.0984503 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.074912 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.083968 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.0795017 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.0928914 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.0941349 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.0829417 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.126903 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.147895 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.135168 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.0860091 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.086016 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.083456 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.127262 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.08944 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.0800914 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.108427 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.0991086 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.0945714 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.0789829 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.0827086 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.0897486 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.133915 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.139264 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.0538697 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.0844069 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.220599 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.0770194 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.0814811 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.0754103 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.0792137 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.129975 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.127342 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.0765074 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.087552 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.109275 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.0718194 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.130048 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.132994 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.0740937 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.130341 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.155794 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.154331 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.0789943 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.0491032 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.0562225 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.0774583 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.0498834 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.127342 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.0780434 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.0776046 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.0551985 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.0564495 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.222062 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.126743 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.111177 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.110811 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.104741 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.0769417 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.0799451 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.086016 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.142921 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.133266 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.0845531 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.0843337 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.126245 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.0826514 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.13568 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.0923063 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.128665 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.230555 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.0786423 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.132946 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.139337 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.131145 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.130926 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.0869691 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.0685592 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.105399 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.0884297 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.0745486 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.139776 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.0810423 +[03/18/2024-15:13:20] [V] [TRT] Fastest Tactic: 0x3e7eb35b91b9fa63 Time: 0.0491032 +[03/18/2024-15:13:20] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CudaDepthwiseConvolution) +[03/18/2024-15:13:20] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (FusedConvActConvolution) +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000007ffff Time: 0.168375 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x00000000000affff Time: 0.334117 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x00000000000effff Time: 0.342766 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x00000000000fffff Time: 0.161792 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000019ffff Time: 0.160914 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x00000000001affff Time: 0.361472 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000024ffff Time: 0.225294 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000027ffff Time: 0.171301 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x00000000002dffff Time: 0.160914 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000036ffff Time: 0.169399 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x00000000004cffff Time: 0.165742 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000062ffff Time: 0.159305 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x00000000006effff Time: 0.418377 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000077ffff Time: 0.212261 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000086ffff Time: 0.38725 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000089ffff Time: 0.197193 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000097ffff Time: 0.340261 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000098ffff Time: 0.202898 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x00000000009fffff Time: 0.201143 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000a2ffff Time: 0.210651 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000a4ffff Time: 0.480402 +[03/18/2024-15:13:20] [V] [TRT] Fastest Tactic: 0x000000000062ffff Time: 0.159305 +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CudnnConvolution) +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.342309 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.384731 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.319049 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.36192 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.51595 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.150235 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.307931 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000039 Time: 0.352256 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000000003a Time: 0.307378 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000000003c Time: 1.2111 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000000003d Time: 0.434907 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000000003e Time: 0.141458 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000070 Time: 0.294181 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000071 Time: 0.294327 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000072 Time: 0.294181 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000074 Time: 1.22105 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000075 Time: 0.402327 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000076 Time: 0.138825 +[03/18/2024-15:13:20] [V] [TRT] Fastest Tactic: 0x0000000000000076 Time: 0.138825 +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskGemmConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 0.249125 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 0.364398 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.385902 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 0.133486 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.64512 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 0.78731 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 0.361472 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 0.376247 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 0.799899 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 0.603282 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.418098 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 0.191621 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 0.404626 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x4727434768e46395 Time: 0.420571 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 0.912823 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 0.752933 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 0.362057 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.413111 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 0.450121 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 0.75232 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 0.422327 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.758638 +[03/18/2024-15:13:20] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 0.133486 +[03/18/2024-15:13:20] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 0.289499 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 0.373029 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 0.26741 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.331904 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 0.318171 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 0.183442 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 1.50747 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 0.2048 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.391461 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.394386 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 0.431397 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 0.346405 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 0.302519 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 0.63371 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 0.178619 +[03/18/2024-15:13:20] [V] [TRT] Fastest Tactic: 0x92ed3100c35fc43e Time: 0.178619 +[03/18/2024-15:13:20] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CudaDepthwiseConvolution) +[03/18/2024-15:13:20] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskGemmConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 0.500882 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.50571 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.544768 +[03/18/2024-15:13:20] [V] [TRT] Fastest Tactic: 0x999e005e3b016ea6 Time: 0.500882 +[03/18/2024-15:13:20] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CudnnConvolution) +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.312174 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.31232 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.369225 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.32228 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.516535 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.207287 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.31115 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000000003a Time: 0.310857 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000000003c Time: 1.29799 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000000003d Time: 0.415744 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x000000000000003e Time: 0.215479 +[03/18/2024-15:13:20] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 0.207287 +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskGemmConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000006 +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (FusedConvActConvolution) +[03/18/2024-15:13:20] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_small_nn_v1 Tactic: 0xea8b68014eaeb55d +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xea8b68014eaeb55d Time: 0.474843 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_medium_nn_v1 Tactic: 0x1e7896ba71ef1635 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x1e7896ba71ef1635 Time: 0.141824 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_winograd_fp16x2_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc754debea88ae0b7 Time: 0.0779931 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_large_nn_v1 Tactic: 0x91f7e9c0851ad67c +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x91f7e9c0851ad67c Time: 0.501321 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_medium_nn_v1 Tactic: 0x360278e347d63410 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x360278e347d63410 Time: 0.434907 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_small_nn_v1 Tactic: 0xc34b78af38b295a7 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc34b78af38b295a7 Time: 0.127927 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_large_nn_v1 Tactic: 0xb837f96ef306f686 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb837f96ef306f686 Time: 0.130414 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_medium_nn_v1 Tactic: 0x4cfee77ea8c324db +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x4cfee77ea8c324db Time: 0.217966 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_large_nn_v1 Tactic: 0x2f735ffbb05a30fd +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x2f735ffbb05a30fd Time: 0.226011 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_small_nn_v1 Tactic: 0x540fde3a7bee53dc +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x540fde3a7bee53dc Time: 0.221769 +[03/18/2024-15:13:20] [V] [TRT] Fastest Tactic: 0xc754debea88ae0b7 Time: 0.0779931 +[03/18/2024-15:13:20] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CudaDepthwiseConvolution) +[03/18/2024-15:13:20] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskGemmConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskFlattenConvolution) +[03/18/2024-15:13:20] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:20] [V] [TRT] --------------- Timing Runner: Conv_64 (CaskConvolution) +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.115712 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.09216 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.158894 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.0887954 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.114688 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.0889234 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.140581 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.138971 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.138466 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.0878331 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.158281 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.140286 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.13941 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.130194 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.113006 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.137947 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.128366 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.149243 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.098656 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.129246 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.0987429 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.0746789 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.0837486 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.07936 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.0924297 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.0947931 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.0830171 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.127561 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.148919 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.136121 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.0861623 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.0839086 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.0826514 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.126391 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.088944 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.0787749 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.107353 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.0981509 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.0939154 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.077984 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.0825783 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.0891611 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.132535 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.138311 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.0546133 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.084992 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.218697 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.0742446 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.0788617 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.0729234 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.0775314 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.125733 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.12288 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.0740206 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.0893806 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.108105 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.0720297 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.128293 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.132535 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.0735817 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.129243 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.151698 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.155648 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.0772389 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.0504198 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.0564526 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:20] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.0774583 +[03/18/2024-15:13:20] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.0511512 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.12917 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.0780297 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.0762149 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.055101 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.0565592 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.22411 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.127342 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.112185 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.108837 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.102699 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.0759954 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.0810377 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.086016 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.142629 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.132827 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.0845669 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.0842491 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.126537 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.082944 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.136704 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.0935497 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.129317 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.232727 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.0775314 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.134144 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.140069 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.131237 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.130999 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.0870286 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.0693394 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.104814 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.0886423 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.074752 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.138898 +[03/18/2024-15:13:21] [V] [TRT] Conv_64 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.0799451 +[03/18/2024-15:13:21] [V] [TRT] Fastest Tactic: 0x3e7eb35b91b9fa63 Time: 0.0504198 +[03/18/2024-15:13:21] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:21] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:21] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CudaDepthwiseConvolution) +[03/18/2024-15:13:21] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (FusedConvActConvolution) +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000007ffff Time: 0.169399 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x00000000000fffff Time: 0.159744 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000019ffff Time: 0.159159 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000024ffff Time: 0.223232 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000027ffff Time: 0.169545 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x00000000002dffff Time: 0.159744 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000036ffff Time: 0.171154 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x00000000004cffff Time: 0.179488 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000062ffff Time: 0.172617 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000077ffff Time: 0.183858 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000086ffff Time: 0.257317 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000089ffff Time: 0.171301 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000097ffff Time: 0.241381 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000098ffff Time: 0.176128 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x00000000009fffff Time: 0.174373 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000a2ffff Time: 0.211383 +[03/18/2024-15:13:21] [V] [TRT] Fastest Tactic: 0x000000000019ffff Time: 0.159159 +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CudnnConvolution) +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.230839 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.349769 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.204654 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.09071 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.397897 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.136338 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.187685 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000039 Time: 0.326363 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003a Time: 0.185906 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003c Time: 0.947931 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003d Time: 0.47616 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003e Time: 0.13195 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000070 Time: 0.182126 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000071 Time: 0.182126 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000072 Time: 0.182126 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000074 Time: 1.10109 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000075 Time: 0.376247 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000076 Time: 0.129609 +[03/18/2024-15:13:21] [V] [TRT] Fastest Tactic: 0x0000000000000076 Time: 0.129609 +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskGemmConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 0.236544 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 0.344197 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.364837 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 0.127406 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.713289 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 0.68213 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 0.436384 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 0.296814 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 0.664567 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 0.577243 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.400091 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 0.183442 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 0.273961 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x4727434768e46395 Time: 0.409746 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 0.912823 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 0.753518 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 0.356937 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.415013 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 0.451589 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 0.857673 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 0.492 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.772242 +[03/18/2024-15:13:21] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 0.127406 +[03/18/2024-15:13:21] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:21] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 0.284672 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 0.366885 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 0.361787 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.390729 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 0.321682 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 0.192805 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 1.40581 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 0.211968 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.36747 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.390875 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 0.428334 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 0.343749 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 0.300763 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 0.811593 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 0.178761 +[03/18/2024-15:13:21] [V] [TRT] Fastest Tactic: 0x92ed3100c35fc43e Time: 0.178761 +[03/18/2024-15:13:21] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:21] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CudaDepthwiseConvolution) +[03/18/2024-15:13:21] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskGemmConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 0.553691 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.596699 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.478208 +[03/18/2024-15:13:21] [V] [TRT] Fastest Tactic: 0xb443c221fcb1565b Time: 0.478208 +[03/18/2024-15:13:21] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:21] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CudnnConvolution) +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.207579 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.207433 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.207433 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000004 Time: 0.857819 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.413989 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000006 Time: 2.06 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.197339 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003a Time: 0.197339 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003c Time: 0.863525 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003d Time: 0.472494 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003e Time: 2.14133 +[03/18/2024-15:13:21] [V] [TRT] Fastest Tactic: 0x0000000000000038 Time: 0.197339 +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskGemmConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000038 +[03/18/2024-15:13:21] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (FusedConvActConvolution) +[03/18/2024-15:13:21] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_small_nn_v1 Tactic: 0xea8b68014eaeb55d +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xea8b68014eaeb55d Time: 0.550473 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_medium_nn_v1 Tactic: 0x1e7896ba71ef1635 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x1e7896ba71ef1635 Time: 0.128809 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_winograd_fp16x2_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc754debea88ae0b7 Time: 0.07424 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_large_nn_v1 Tactic: 0x91f7e9c0851ad67c +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x91f7e9c0851ad67c Time: 0.441783 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_medium_nn_v1 Tactic: 0x360278e347d63410 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x360278e347d63410 Time: 0.4864 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_small_nn_v1 Tactic: 0xc34b78af38b295a7 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc34b78af38b295a7 Time: 0.126969 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_large_nn_v1 Tactic: 0xb837f96ef306f686 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xb837f96ef306f686 Time: 0.129893 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_medium_nn_v1 Tactic: 0x4cfee77ea8c324db +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x4cfee77ea8c324db Time: 0.215771 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_large_nn_v1 Tactic: 0x2f735ffbb05a30fd +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x2f735ffbb05a30fd Time: 0.217234 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_small_nn_v1 Tactic: 0x540fde3a7bee53dc +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x540fde3a7bee53dc Time: 0.213285 +[03/18/2024-15:13:21] [V] [TRT] Fastest Tactic: 0xc754debea88ae0b7 Time: 0.07424 +[03/18/2024-15:13:21] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:21] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CudaDepthwiseConvolution) +[03/18/2024-15:13:21] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskGemmConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:21] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.111326 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.0893074 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.159013 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.0906971 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.116882 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.0909897 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.133925 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.132752 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.131257 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.0838949 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.152283 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.135387 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.13451 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.129682 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.11176 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.136485 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.128219 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.149797 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.09896 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.129463 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.0983771 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.075264 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.0840411 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.0797257 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.0930446 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.0965714 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.0838217 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.12845 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.149797 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.13669 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.0871131 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.0853577 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.0845577 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.128585 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.0900251 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.0797989 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.108178 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.0986697 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.0941989 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.0791406 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.0828457 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.0898194 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.135168 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.142043 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.0527741 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.0852206 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.223086 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.0759223 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.0802377 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.0747497 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.0789943 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.129223 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.126318 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.0762149 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.0879177 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.10955 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.0741669 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.131145 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.133851 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.0748251 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.131584 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.155209 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.156379 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.0789897 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.0495421 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.0566613 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.0781166 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.050176 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.131365 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.0787749 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.077824 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.0553935 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.0571855 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.22971 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.130706 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.114688 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.111559 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.105326 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.0774491 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.079584 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.0857966 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.142336 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.132681 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.0844069 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.083968 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.126098 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.0827977 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.138094 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.092352 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.128597 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.230693 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.0784823 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.132974 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.139191 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.132242 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.132096 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.0876251 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.0690956 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.106057 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.0915817 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.0749143 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.140197 +[03/18/2024-15:13:21] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.0816274 +[03/18/2024-15:13:21] [V] [TRT] Fastest Tactic: 0x3e7eb35b91b9fa63 Time: 0.0495421 +[03/18/2024-15:13:21] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:21] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CudaDepthwiseConvolution) +[03/18/2024-15:13:21] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (FusedConvActConvolution) +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000007ffff Time: 0.168521 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x00000000000fffff Time: 0.161938 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000019ffff Time: 0.161061 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000024ffff Time: 0.225865 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000027ffff Time: 0.171593 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x00000000002dffff Time: 0.161513 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000036ffff Time: 0.172325 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x00000000004cffff Time: 0.174226 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000062ffff Time: 0.167643 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000077ffff Time: 0.178469 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000086ffff Time: 0.24971 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000089ffff Time: 0.166327 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000097ffff Time: 0.23552 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000098ffff Time: 0.171008 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x00000000009fffff Time: 0.169545 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000a2ffff Time: 0.210505 +[03/18/2024-15:13:21] [V] [TRT] Fastest Tactic: 0x000000000019ffff Time: 0.161061 +[03/18/2024-15:13:21] [V] [TRT] --------------- Timing Runner: Conv_67 (CudnnConvolution) +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.223525 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.375223 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.223671 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.09887 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.435931 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.150674 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.208896 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000039 Time: 0.337774 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003a Time: 0.196169 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003c Time: 0.969289 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003d Time: 0.392923 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x000000000000003e Time: 0.135241 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000070 Time: 0.186661 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000071 Time: 0.186661 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000072 Time: 0.186661 +[03/18/2024-15:13:21] [V] [TRT] Tactic: 0x0000000000000074 Time: 0.945166 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000075 Time: 0.471058 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000076 Time: 0.13173 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0x0000000000000076 Time: 0.13173 +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskGemmConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 0.233179 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 0.339383 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.360009 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 0.125513 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.746496 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 0.647753 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 0.344357 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 0.349915 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 0.840265 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 0.591287 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.500151 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 0.190757 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 0.283502 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x4727434768e46395 Time: 0.420279 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 0.816713 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 0.753664 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 0.289499 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.423497 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 0.461093 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 0.780727 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 0.443831 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.868498 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 0.125513 +[03/18/2024-15:13:22] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 0.42101 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 0.379918 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 0.271506 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.338066 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 0.440649 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 0.190171 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 1.36372 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 0.211113 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.367909 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.514194 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 0.425106 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 0.448805 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 0.3584 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 0.625957 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 0.175982 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0x92ed3100c35fc43e Time: 0.175982 +[03/18/2024-15:13:22] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CudaDepthwiseConvolution) +[03/18/2024-15:13:22] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskGemmConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 0.493861 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.503808 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.469577 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0xb443c221fcb1565b Time: 0.469577 +[03/18/2024-15:13:22] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CudnnConvolution) +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.204046 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.204069 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.203776 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000004 Time: 0.927598 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.426235 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.200553 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.191781 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000000003a Time: 0.191781 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000000003c Time: 1.03863 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000000003d Time: 0.404041 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000000003e Time: 0.206555 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0x0000000000000038 Time: 0.191781 +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskGemmConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000038 +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (FusedConvActConvolution) +[03/18/2024-15:13:22] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_small_nn_v1 Tactic: 0xea8b68014eaeb55d +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xea8b68014eaeb55d Time: 0.445879 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_medium_nn_v1 Tactic: 0x1e7896ba71ef1635 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x1e7896ba71ef1635 Time: 0.130999 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_winograd_fp16x2_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc754debea88ae0b7 Time: 0.0751909 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_large_nn_v1 Tactic: 0x91f7e9c0851ad67c +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x91f7e9c0851ad67c Time: 0.449097 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_medium_nn_v1 Tactic: 0x360278e347d63410 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x360278e347d63410 Time: 0.438711 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_small_nn_v1 Tactic: 0xc34b78af38b295a7 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc34b78af38b295a7 Time: 0.128955 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_large_nn_v1 Tactic: 0xb837f96ef306f686 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xb837f96ef306f686 Time: 0.130999 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_medium_nn_v1 Tactic: 0x4cfee77ea8c324db +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x4cfee77ea8c324db Time: 0.216503 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_large_nn_v1 Tactic: 0x2f735ffbb05a30fd +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x2f735ffbb05a30fd Time: 0.218112 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_small_nn_v1 Tactic: 0x540fde3a7bee53dc +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x540fde3a7bee53dc Time: 0.214025 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0xc754debea88ae0b7 Time: 0.0751909 +[03/18/2024-15:13:22] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CudaDepthwiseConvolution) +[03/18/2024-15:13:22] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskGemmConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_67 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.110885 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.0879909 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.15989 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.0898194 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.11637 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.089904 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.14189 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.137435 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.133339 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.0846994 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.154299 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.136862 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.136121 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.126757 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.110747 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.134144 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.126098 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.14731 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.09728 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.127333 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.0972069 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.0736549 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.0824183 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.0779063 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.0918674 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.094208 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.0837463 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.126619 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.147749 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.135013 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.0856594 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.0845531 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.0831634 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.126757 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.0890126 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.0791406 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.107568 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.0982903 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.093696 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.0782126 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.0825783 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.0891611 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.132901 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.138021 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.0546149 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.0833829 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.217381 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.073856 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.0787017 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.0726971 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.0776937 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.125952 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.123246 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.0740937 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.0866011 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.108987 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.0713021 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.126757 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.129093 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.0727771 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.127342 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.149504 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.150528 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.074752 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.0498834 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.0561737 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.0762149 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.0506636 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.126699 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.0765806 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.0748251 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.0549547 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.0559771 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.224402 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.128 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.112933 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.109662 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.103497 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.0764251 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.0782629 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.0853577 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.143141 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.130421 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.0830994 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.0827977 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.124343 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.081392 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.133109 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.0920869 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.127049 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.228069 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.0762149 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.132242 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.137746 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.129975 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.129609 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.086016 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.068608 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.103863 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.0877714 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.0741737 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.137801 +[03/18/2024-15:13:22] [V] [TRT] Conv_67 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.0796526 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0x3e7eb35b91b9fa63 Time: 0.0498834 +[03/18/2024-15:13:22] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:22] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CudaDepthwiseConvolution) +[03/18/2024-15:13:22] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (FusedConvActConvolution) +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000007ffff Time: 0.165888 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x00000000000fffff Time: 0.159305 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000019ffff Time: 0.158866 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000024ffff Time: 0.221477 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000027ffff Time: 0.168667 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x00000000002dffff Time: 0.1584 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000036ffff Time: 0.166766 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x00000000004cffff Time: 0.163109 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000062ffff Time: 0.172325 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000077ffff Time: 0.190757 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000086ffff Time: 0.265655 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000089ffff Time: 0.177879 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000097ffff Time: 0.360562 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000098ffff Time: 0.182418 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x00000000009fffff Time: 0.181577 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000a2ffff Time: 0.18944 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0x00000000002dffff Time: 0.1584 +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CudnnConvolution) +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.519753 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.385317 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.515218 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.82287 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.513147 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.158135 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.428891 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000039 Time: 0.367909 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000000003a Time: 0.420425 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000000003c Time: 1.76889 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000000003d Time: 0.433737 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x000000000000003e Time: 0.151113 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000070 Time: 0.397019 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000071 Time: 0.396727 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000072 Time: 0.455387 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000074 Time: 1.69648 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000075 Time: 0.495031 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000076 Time: 0.149504 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0x0000000000000076 Time: 0.149504 +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskGemmConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 0.384 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 0.360741 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.382245 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 0.132681 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.738597 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 0.708315 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 0.455973 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 0.309248 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 0.70336 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 0.640585 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.520338 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 0.186953 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 0.281454 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x4727434768e46395 Time: 0.515511 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 0.788041 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 0.750153 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 0.291255 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.423497 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 0.461093 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 0.979968 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 0.442075 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.876105 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 0.132681 +[03/18/2024-15:13:22] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 0.296375 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 0.380928 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 0.273262 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.338359 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 0.334263 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 0.19605 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 1.62743 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 0.215479 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.384585 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.394843 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 0.432 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 0.346834 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 0.304567 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 0.701879 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 0.180078 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0x92ed3100c35fc43e Time: 0.180078 +[03/18/2024-15:13:22] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CudaDepthwiseConvolution) +[03/18/2024-15:13:22] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskGemmConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:22] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 0.619959 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.499566 +[03/18/2024-15:13:22] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.482743 +[03/18/2024-15:13:22] [V] [TRT] Fastest Tactic: 0xb443c221fcb1565b Time: 0.482743 +[03/18/2024-15:13:22] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:22] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:22] [V] [TRT] --------------- Timing Runner: Conv_70 (CudnnConvolution) +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.868791 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.252603 +[03/18/2024-15:13:22] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.976443 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.58326 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.563346 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000006 Time: 2.34759 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.905947 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003a Time: 1.08061 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003c Time: 1.8549 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003d Time: 0.480969 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003e Time: 2.15391 +[03/18/2024-15:13:23] [V] [TRT] Fastest Tactic: 0x0000000000000001 Time: 0.252603 +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskGemmConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000001 +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (FusedConvActConvolution) +[03/18/2024-15:13:23] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_small_nn_v1 Tactic: 0xea8b68014eaeb55d +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xea8b68014eaeb55d Time: 0.469138 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_medium_nn_v1 Tactic: 0x1e7896ba71ef1635 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x1e7896ba71ef1635 Time: 0.140069 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_winograd_fp16x2_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc754debea88ae0b7 Time: 0.080384 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_large_nn_v1 Tactic: 0x91f7e9c0851ad67c +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x91f7e9c0851ad67c Time: 0.480402 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_medium_nn_v1 Tactic: 0x360278e347d63410 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x360278e347d63410 Time: 0.448512 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_small_nn_v1 Tactic: 0xc34b78af38b295a7 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc34b78af38b295a7 Time: 0.132014 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_large_nn_v1 Tactic: 0xb837f96ef306f686 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb837f96ef306f686 Time: 0.134427 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_medium_nn_v1 Tactic: 0x4cfee77ea8c324db +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x4cfee77ea8c324db Time: 0.223232 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_large_nn_v1 Tactic: 0x2f735ffbb05a30fd +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x2f735ffbb05a30fd Time: 0.207287 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_small_nn_v1 Tactic: 0x540fde3a7bee53dc +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x540fde3a7bee53dc Time: 0.203483 +[03/18/2024-15:13:23] [V] [TRT] Fastest Tactic: 0xc754debea88ae0b7 Time: 0.080384 +[03/18/2024-15:13:23] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CudaDepthwiseConvolution) +[03/18/2024-15:13:23] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskGemmConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.107301 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.0857714 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.151845 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.0854949 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.110443 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.0857234 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.135387 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.135387 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.132827 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.0848457 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.156233 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.138971 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.13824 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.128658 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.111835 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.134802 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.126873 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.147895 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.0978149 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.128 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.0976457 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.0748983 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.0833851 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.0790903 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.0941349 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.0947931 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.083456 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.127488 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.148773 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.135904 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.0865943 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.0858606 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.08704 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.132681 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.0927451 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.0830903 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.113223 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.103205 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.0987451 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.0837486 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.0857966 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.0930834 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.139781 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.145554 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.0528518 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.0879954 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.231131 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.078336 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.0827977 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.0765051 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.0807566 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.133193 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.130357 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.078336 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.090112 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.112718 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.0740937 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.134368 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.13707 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.0767726 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.135314 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.161353 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.161061 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.0800914 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.0504823 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.0587535 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.0803931 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.0507611 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.131511 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.0807497 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.0785349 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.0570514 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.0586149 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.231264 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.132901 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.1152 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.112274 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.105691 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.0776046 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.0803109 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.0867474 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.144384 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.132535 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.0842606 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.0842606 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.126245 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.0825166 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.135739 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.0923063 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.128663 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.2304 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.078608 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.133125 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.138825 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.131072 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.130633 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.0866011 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.0682118 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.104592 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.087552 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.0740091 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.138386 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.0804571 +[03/18/2024-15:13:23] [V] [TRT] Fastest Tactic: 0x3e7eb35b91b9fa63 Time: 0.0504823 +[03/18/2024-15:13:23] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CudaDepthwiseConvolution) +[03/18/2024-15:13:23] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (FusedConvActConvolution) +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000007ffff Time: 0.169984 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x00000000000fffff Time: 0.161353 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000019ffff Time: 0.165449 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000024ffff Time: 0.223963 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000027ffff Time: 0.170862 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x00000000002dffff Time: 0.160183 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000036ffff Time: 0.168082 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x00000000004cffff Time: 0.165029 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000062ffff Time: 0.15872 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000077ffff Time: 0.168521 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000086ffff Time: 0.277943 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000089ffff Time: 0.185929 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000097ffff Time: 0.261998 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000098ffff Time: 0.191634 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x00000000009fffff Time: 0.189842 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000a2ffff Time: 0.19851 +[03/18/2024-15:13:23] [V] [TRT] Fastest Tactic: 0x000000000062ffff Time: 0.15872 +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CudnnConvolution) +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.492105 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.385024 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.454656 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.61412 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.44208 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.149504 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.406821 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000039 Time: 0.441783 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003a Time: 0.46795 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003c Time: 1.7739 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003d Time: 0.420425 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003e Time: 0.144251 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000070 Time: 0.399214 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000071 Time: 0.398629 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000072 Time: 0.398629 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000074 Time: 1.65888 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000075 Time: 0.471625 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000076 Time: 0.146139 +[03/18/2024-15:13:23] [V] [TRT] Fastest Tactic: 0x000000000000003e Time: 0.144251 +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskGemmConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 0.266085 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 0.390738 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.397897 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 0.129463 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.750299 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 0.675694 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 0.365422 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 0.428325 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 0.797696 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 0.591854 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.412526 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 0.188709 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 0.284233 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x4727434768e46395 Time: 0.41472 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 0.813934 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 0.831488 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 0.291694 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.488448 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 0.461243 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 0.765659 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 0.43285 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.876544 +[03/18/2024-15:13:23] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 0.129463 +[03/18/2024-15:13:23] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 0.294473 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 0.378734 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 0.27136 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.330021 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 0.381367 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 0.184334 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 1.32432 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 0.226889 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.396142 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.39819 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 0.435785 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 0.350185 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 0.305737 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 0.639415 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 0.180078 +[03/18/2024-15:13:23] [V] [TRT] Fastest Tactic: 0x92ed3100c35fc43e Time: 0.180078 +[03/18/2024-15:13:23] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CudaDepthwiseConvolution) +[03/18/2024-15:13:23] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskGemmConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 0.506002 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.51595 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.569783 +[03/18/2024-15:13:23] [V] [TRT] Fastest Tactic: 0x999e005e3b016ea6 Time: 0.506002 +[03/18/2024-15:13:23] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CudnnConvolution) +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.788773 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.248539 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000002 Time: 1.00688 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.85432 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.453486 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.223525 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x0000000000000038 Time: 1.01727 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003a Time: 1.00001 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003c Time: 1.84759 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003d Time: 0.525152 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x000000000000003e Time: 0.230254 +[03/18/2024-15:13:23] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 0.223525 +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskGemmConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000006 +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (FusedConvActConvolution) +[03/18/2024-15:13:23] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_small_nn_v1 Tactic: 0xea8b68014eaeb55d +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xea8b68014eaeb55d Time: 0.611621 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_medium_nn_v1 Tactic: 0x1e7896ba71ef1635 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x1e7896ba71ef1635 Time: 0.149504 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_winograd_fp16x2_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc754debea88ae0b7 Time: 0.0856503 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_large_nn_v1 Tactic: 0x91f7e9c0851ad67c +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x91f7e9c0851ad67c Time: 0.48757 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_medium_nn_v1 Tactic: 0x360278e347d63410 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x360278e347d63410 Time: 0.446318 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_small_nn_v1 Tactic: 0xc34b78af38b295a7 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc34b78af38b295a7 Time: 0.132041 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_large_nn_v1 Tactic: 0xb837f96ef306f686 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb837f96ef306f686 Time: 0.133851 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_medium_nn_v1 Tactic: 0x4cfee77ea8c324db +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x4cfee77ea8c324db Time: 0.222208 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_large_nn_v1 Tactic: 0x2f735ffbb05a30fd +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x2f735ffbb05a30fd Time: 0.223817 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_small_nn_v1 Tactic: 0x540fde3a7bee53dc +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x540fde3a7bee53dc Time: 0.22043 +[03/18/2024-15:13:23] [V] [TRT] Fastest Tactic: 0xc754debea88ae0b7 Time: 0.0856503 +[03/18/2024-15:13:23] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CudaDepthwiseConvolution) +[03/18/2024-15:13:23] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskGemmConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskFlattenConvolution) +[03/18/2024-15:13:23] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:23] [V] [TRT] --------------- Timing Runner: Conv_70 (CaskConvolution) +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.115495 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.0917211 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.164279 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.09152 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.114395 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.0872777 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.137582 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.136338 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.135753 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.0863291 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.157403 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.13941 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.138606 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.129317 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.112421 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.137143 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.130487 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.150382 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.0992549 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.130267 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.0992549 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.0754103 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.0842606 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:23] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.0796526 +[03/18/2024-15:13:23] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.0939154 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.0960206 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.0833097 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.127927 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.149504 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.136645 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.086528 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.0849189 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.0840411 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.128331 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.08984 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.0797989 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.109808 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.099328 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.0949486 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.0791406 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.0835292 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.0897463 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.134217 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.140215 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.0529554 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.0845006 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.22133 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.0748343 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.0795794 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.0735086 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.0789943 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.130048 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.127122 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.0761417 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.0888686 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.110299 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.0735817 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.131447 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.133559 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.0749806 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.135095 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.159451 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.161061 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.0792846 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.0518293 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.0576366 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.0792114 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.0521265 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.132681 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.07936 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.0778971 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.056701 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.0579718 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.23467 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.131145 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.115127 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.111982 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.106498 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.0792777 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.0817074 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.0889303 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.147328 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.137223 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.0871863 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.0869669 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.129097 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.0849691 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.136704 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.0934766 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.129536 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.232741 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.0772389 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.133705 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.138606 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.130779 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.130567 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.0866011 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.0690469 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.104706 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.0879794 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.0739474 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.137362 +[03/18/2024-15:13:24] [V] [TRT] Conv_70 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.0795109 +[03/18/2024-15:13:24] [V] [TRT] Fastest Tactic: 0x3e7eb35b91b9fa63 Time: 0.0518293 +[03/18/2024-15:13:24] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_73 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_73 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_73 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_73 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_73 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_73 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_73 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_73 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_76 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_76 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_76 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_76 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_76 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_76 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_76 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_76 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_79 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_79 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_79 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_79 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_79 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_79 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_79 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_79 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_82 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_82 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_82 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_82 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_82 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_82 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_82 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_82 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_85 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_85 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_85 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_85 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_85 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_85 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_85 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_85 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_88 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_88 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_88 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_88 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_88 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_88 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_88 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_88 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_91 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_91 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_91 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_91 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_91 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_91 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_91 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_91 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_94 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_94 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_94 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_94 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_94 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_94 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_94 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_94 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_97 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_97 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_97 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_97 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_97 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_97 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_97 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_97 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_100 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_100 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_100 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_100 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_100 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_100 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_100 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_100 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_103 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_103 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_103 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_103 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_103 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_103 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_103 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_103 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_106 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_106 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_106 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_106 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_106 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_106 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_106 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_106 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_109 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_109 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_109 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_109 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_109 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_109 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_109 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_109 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_112 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_112 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_112 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_112 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_112 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_112 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_112 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_112 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_115 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_115 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_115 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_115 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_115 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_115 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_115 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_115 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_118 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_118 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_118 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_118 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_118 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_118 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_118 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_118 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_121 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_121 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_121 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_121 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_121 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_121 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_121 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_121 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_124 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_124 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_124 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_124 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_124 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_124 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_124 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_124 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_127 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_127 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_127 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_127 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_127 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_127 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_127 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_127 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_130 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_130 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_130 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_130 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_130 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_130 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_130 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_130 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_133 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_133 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_133 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_133 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_133 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_133 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_133 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_133 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(16588800,1,92160,512) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(4147200,1:4,23040,128) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(16588800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(8294400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(4147200,1:4,23040,128) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(16588800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(2073600,1:8,11520,64) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_136 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_136 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_136 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_136 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_136 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_136 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_136 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_136 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_139 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_139 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_139 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_139 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_139 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_139 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_139 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_139 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_142 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_142 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_142 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_142 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_142 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_142 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_142 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_142 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_145 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_145 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_145 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_145 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_145 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_145 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_145 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_145 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_148 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_148 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_148 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_148 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_148 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_148 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_148 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_148 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_151 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_151 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_151 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_151 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_151 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_151 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_151 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_151 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_154 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_154 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_154 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_154 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_154 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_154 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_154 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_154 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,32400,180,1) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(16588800,1,92160,512) long-strided -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(4147200,1:4,23040,128) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(16588800,32400,180,1) long-strided -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(4147200,1:4,23040,128) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_157 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_157 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_157 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_157 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:8,11520,64) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(32400,1,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_157 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_157 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(32400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_157 (CaskFlattenConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_157 (CaskConvolution) +[03/18/2024-15:13:24] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:24] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CudaDepthwiseConvolution) +[03/18/2024-15:13:24] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (FusedConvActConvolution) +[03/18/2024-15:13:24] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:24] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CudnnConvolution) +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.51685 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x0000000000000001 Time: 1.95584 +[03/18/2024-15:13:24] [V] [TRT] Tactic: 0x0000000000000002 Time: 2.84292 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x0000000000000005 Time: 12.0832 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x0000000000000006 Time: 2.03866 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x0000000000000038 Time: 2.86632 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x0000000000000039 Time: 1.98789 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x000000000000003a Time: 2.78981 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x000000000000003d Time: 12.1107 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x000000000000003e Time: 1.89893 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x0000000000000070 Time: 2.76378 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x0000000000000071 Time: 2.3002 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x0000000000000072 Time: 2.97106 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x0000000000000075 Time: 12.3377 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x0000000000000076 Time: 1.90391 +[03/18/2024-15:13:25] [V] [TRT] Fastest Tactic: 0x000000000000003e Time: 1.89893 +[03/18/2024-15:13:25] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskGemmConvolution) +[03/18/2024-15:13:25] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:25] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskFlattenConvolution) +[03/18/2024-15:13:25] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:25] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskConvolution) +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 2.02958 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 1.53963 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 1.92977 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 1.25484 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 1.79156 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 1.8293 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 3.96025 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 5.89312 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 1.75324 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 2.88168 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 2.24607 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 3.78617 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 3.4029 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x4727434768e46395 Time: 2.88459 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 2.25017 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 2.20482 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 2.85345 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 1.99183 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 2.20994 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 1.79888 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 3.8223 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 1.7506 +[03/18/2024-15:13:25] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 1.25484 +[03/18/2024-15:13:25] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:25] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(8294400,1,46080,256) *************** +[03/18/2024-15:13:25] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskFlattenConvolution) +[03/18/2024-15:13:25] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:25] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskConvolution) +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x27b316f52c109002 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x27b316f52c109002 Time: 1.70774 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x128_relu_exp_medium_nhwc_tn_v1 Tactic: 0xd9031472c05adf51 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xd9031472c05adf51 Time: 1.4434 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0x3e2b881168d9689d +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0x3e2b881168d9689d Time: 1.91517 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_small_nhwc_tn_v1 Tactic: 0xf90060ce8193b811 +[03/18/2024-15:13:25] [V] [TRT] Tactic: 0xf90060ce8193b811 Time: 1.57682 +[03/18/2024-15:13:25] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0xbdfdef6b84f7ccc9 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xbdfdef6b84f7ccc9 Time: 1.85915 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x64_sliced1x2_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x412c44dfeaf9161d +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x412c44dfeaf9161d Time: 1.88928 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x7bc32c782b800c48 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x7bc32c782b800c48 Time: 1.59949 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 3.09628 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 2.12392 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 2.64016 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 1.55238 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x32_sliced1x4_ldg4_relu_exp_medium_nhwc_tn_v1 Tactic: 0x3e191488237fab8f +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x3e191488237fab8f Time: 2.33547 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 3.53938 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 3.4519 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 1.88913 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 4.19739 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 1.87904 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 1.71608 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x128_relu_exp_large_nhwc_tn_v1 Tactic: 0xca7eeb8d9143d738 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xca7eeb8d9143d738 Time: 1.62728 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 2.10944 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 1.54887 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x128_relu_exp_small_nhwc_tn_v1 Tactic: 0x5030121339a48bf3 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x5030121339a48bf3 Time: 1.81731 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 3.27648 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 1.63796 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 3.19517 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_scudnn_128x128_ldg4_relu_exp_large_nhwc_tn_v1 Tactic: 0x634e99502974e4da +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x634e99502974e4da Time: 1.58062 +[03/18/2024-15:13:26] [V] [TRT] Fastest Tactic: 0xd9031472c05adf51 Time: 1.4434 +[03/18/2024-15:13:26] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xd9031472c05adf51 +[03/18/2024-15:13:26] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(2073600,1:4,11520,64) *************** +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CudaDepthwiseConvolution) +[03/18/2024-15:13:26] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskGemmConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskFlattenConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskConvolution) +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 1.24945 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 1.09729 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 1.14966 +[03/18/2024-15:13:26] [V] [TRT] Fastest Tactic: 0x65e41d81f093b482 Time: 1.09729 +[03/18/2024-15:13:26] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:26] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(8294400,32400,180,1) *************** +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CudnnConvolution) +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x0000000000000000 Time: 2.77211 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x0000000000000001 Time: 3.42967 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x0000000000000002 Time: 2.94707 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x0000000000000005 Time: 11.7208 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x0000000000000006 Time: 2.13665 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x0000000000000038 Time: 3.62598 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x000000000000003a Time: 2.85389 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x000000000000003d Time: 11.9798 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x000000000000003e Time: 2.15479 +[03/18/2024-15:13:26] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 2.13665 +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskGemmConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskFlattenConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000006 +[03/18/2024-15:13:26] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(4147200,32400:2,180,1) *************** +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (FusedConvActConvolution) +[03/18/2024-15:13:26] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskFlattenConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskConvolution) +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_small_nn_v1 Tactic: 0xea8b68014eaeb55d +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xea8b68014eaeb55d Time: 1.19486 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_medium_nn_v1 Tactic: 0x1e7896ba71ef1635 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x1e7896ba71ef1635 Time: 1.18389 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_fp16x2_hcudnn_winograd_fp16x2_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xc754debea88ae0b7 Time: 0.629029 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_large_nn_v1 Tactic: 0x91f7e9c0851ad67c +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x91f7e9c0851ad67c Time: 1.01566 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_medium_nn_v1 Tactic: 0x360278e347d63410 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x360278e347d63410 Time: 1.03088 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_small_nn_v1 Tactic: 0xc34b78af38b295a7 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xc34b78af38b295a7 Time: 1.13298 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_large_nn_v1 Tactic: 0xb837f96ef306f686 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xb837f96ef306f686 Time: 0.996187 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_medium_nn_v1 Tactic: 0x4cfee77ea8c324db +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x4cfee77ea8c324db Time: 0.957897 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_large_nn_v1 Tactic: 0x2f735ffbb05a30fd +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x2f735ffbb05a30fd Time: 1.26215 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_small_nn_v1 Tactic: 0x540fde3a7bee53dc +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x540fde3a7bee53dc Time: 0.980992 +[03/18/2024-15:13:26] [V] [TRT] Fastest Tactic: 0xc754debea88ae0b7 Time: 0.629029 +[03/18/2024-15:13:26] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:26] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(2073600,1:4,11520,64) *************** +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskFlattenConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(8294400,32400,180,1) *************** +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskFlattenConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(1036800,1:8,5760,32) *************** +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CudaDepthwiseConvolution) +[03/18/2024-15:13:26] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskGemmConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskFlattenConvolution) +[03/18/2024-15:13:26] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:26] [V] [TRT] --------------- Timing Runner: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (CaskConvolution) +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.63371 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.362949 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.356645 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.37877 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.24971 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.384878 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.312937 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.33296 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.308549 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:26] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.363959 +[03/18/2024-15:13:26] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.381952 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.348631 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.337335 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.304128 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.60208 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.334702 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.389413 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.37771 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.478793 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.318757 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.474112 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.390875 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.375515 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.357669 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.448805 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.549303 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.376978 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.386341 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.429623 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.321536 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.388096 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.323397 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.379319 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.305883 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.378441 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.357961 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.516389 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.474258 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.456558 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.420133 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.507758 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.37771 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.314368 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.353865 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.502784 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.378587 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.296229 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.450999 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.497225 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.32256 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.291255 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.35445 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.356937 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.345234 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.368786 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.252343 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.736402 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.297691 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.302665 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.309248 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.404773 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.37771 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.379173 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.287744 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.404919 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.396608 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.270043 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.496933 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.422327 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.284379 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.298277 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.433989 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.440466 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.311296 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.313024 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.272983 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.65653 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.499858 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.332082 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.374199 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.570222 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.361911 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.319781 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.361911 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.478501 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.30837 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.370103 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.365861 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.594066 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.294912 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.299447 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.293449 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.320512 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.321829 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.300032 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.366007 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.586021 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.703488 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.495177 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.42496 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.677742 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.317001 +[03/18/2024-15:13:27] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.353573 +[03/18/2024-15:13:27] [V] [TRT] Fastest Tactic: 0xa927df92ac1ef1b8 Time: 0.24971 +[03/18/2024-15:13:27] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:27] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:27] [V] [TRT] *************** Autotuning format combination: Float(8294400,32400,180,1) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CudaDepthwiseConvolution) +[03/18/2024-15:13:27] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (FusedConvActConvolution) +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000007ffff Time: 0.193253 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x00000000000fffff Time: 0.187685 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000019ffff Time: 0.186368 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000024ffff Time: 0.256585 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000027ffff Time: 0.196754 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x00000000002dffff Time: 0.183442 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000036ffff Time: 0.192667 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x00000000004cffff Time: 0.189294 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000062ffff Time: 0.182272 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000077ffff Time: 0.19456 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000086ffff Time: 0.270921 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000089ffff Time: 0.192366 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000097ffff Time: 0.282478 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000098ffff Time: 0.205824 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x00000000009fffff Time: 0.204361 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000a2ffff Time: 0.214162 +[03/18/2024-15:13:27] [V] [TRT] Fastest Tactic: 0x000000000062ffff Time: 0.182272 +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CudnnConvolution) +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.520923 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.376686 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.436955 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.75938 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.747072 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.147602 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.398921 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000039 Time: 0.345381 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000000003a Time: 0.516974 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000000003c Time: 1.68521 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000000003d Time: 0.431387 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000000003e Time: 0.148942 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000070 Time: 0.557495 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000071 Time: 0.404187 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000072 Time: 0.403899 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000074 Time: 1.72939 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000075 Time: 0.417792 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000076 Time: 0.154039 +[03/18/2024-15:13:27] [V] [TRT] Fastest Tactic: 0x0000000000000006 Time: 0.147602 +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskGemmConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskFlattenConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskConvolution) +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 0.271799 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 0.400238 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.516096 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 0.132462 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.651557 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 0.814958 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 0.382126 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 0.323877 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 0.84085 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 0.583534 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.410153 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 0.19061 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 0.359717 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x4727434768e46395 Time: 0.413111 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 0.718994 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 0.974967 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 0.288914 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.419401 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 0.515365 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 0.761417 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 0.431104 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.773413 +[03/18/2024-15:13:27] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 0.132462 +[03/18/2024-15:13:27] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:27] [V] [TRT] *************** Autotuning format combination: Float(8294400,1,46080,256) long-strided -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskFlattenConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskConvolution) +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 0.416475 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 0.379611 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 0.250025 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.308795 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 0.371273 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 0.182857 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 1.34293 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 0.222062 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.499858 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.386926 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 0.423936 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 0.357522 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 0.4096 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 0.65653 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 0.185344 +[03/18/2024-15:13:27] [V] [TRT] Fastest Tactic: 0x32059de4888dfdda Time: 0.182857 +[03/18/2024-15:13:27] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:27] [V] [TRT] *************** Autotuning format combination: Float(2073600,1:4,11520,64) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CudaDepthwiseConvolution) +[03/18/2024-15:13:27] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskGemmConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskFlattenConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskConvolution) +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 0.519314 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.625234 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.599625 +[03/18/2024-15:13:27] [V] [TRT] Fastest Tactic: 0x999e005e3b016ea6 Time: 0.519314 +[03/18/2024-15:13:27] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:27] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400,180,1) long-strided -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CudnnConvolution) +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.769463 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.256731 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.924818 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.69484 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.506587 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000006 Time: 2.28528 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x0000000000000038 Time: 1.02927 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000000003a Time: 1.01449 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000000003c Time: 1.79961 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000000003d Time: 0.531721 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x000000000000003e Time: 2.24432 +[03/18/2024-15:13:27] [V] [TRT] Fastest Tactic: 0x0000000000000001 Time: 0.256731 +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskGemmConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskFlattenConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000001 +[03/18/2024-15:13:27] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400:2,180,1) long-strided -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (FusedConvActConvolution) +[03/18/2024-15:13:27] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskFlattenConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskConvolution) +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_small_nn_v1 Tactic: 0xea8b68014eaeb55d +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xea8b68014eaeb55d Time: 0.584997 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_medium_nn_v1 Tactic: 0x1e7896ba71ef1635 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x1e7896ba71ef1635 Time: 0.148645 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_fp16x2_hcudnn_winograd_fp16x2_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc754debea88ae0b7 Time: 0.0847726 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_large_nn_v1 Tactic: 0x91f7e9c0851ad67c +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x91f7e9c0851ad67c Time: 0.504978 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_medium_nn_v1 Tactic: 0x360278e347d63410 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x360278e347d63410 Time: 0.4352 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_small_nn_v1 Tactic: 0xc34b78af38b295a7 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc34b78af38b295a7 Time: 0.127854 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_large_nn_v1 Tactic: 0xb837f96ef306f686 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xb837f96ef306f686 Time: 0.130414 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_medium_nn_v1 Tactic: 0x4cfee77ea8c324db +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x4cfee77ea8c324db Time: 0.216503 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_large_nn_v1 Tactic: 0x2f735ffbb05a30fd +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x2f735ffbb05a30fd Time: 0.226304 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_small_nn_v1 Tactic: 0x540fde3a7bee53dc +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x540fde3a7bee53dc Time: 0.223671 +[03/18/2024-15:13:27] [V] [TRT] Fastest Tactic: 0xc754debea88ae0b7 Time: 0.0847726 +[03/18/2024-15:13:27] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:27] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:4,11520,64) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskFlattenConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:8,5760,32) long-strided -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskFlattenConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:8,5760,32) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CudaDepthwiseConvolution) +[03/18/2024-15:13:27] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskGemmConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskFlattenConvolution) +[03/18/2024-15:13:27] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:27] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskConvolution) +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.116955 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.0934766 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.166912 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.0892869 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.115493 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.0895931 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.141678 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.140654 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.138752 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.0884114 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.160183 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.141102 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.140215 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.131067 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:27] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.11381 +[03/18/2024-15:13:27] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.138752 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.130046 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.150528 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.0997028 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.130487 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.0992503 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.0759954 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.0846103 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.0798926 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.0934034 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.0968526 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.0840411 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.129241 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.150528 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.137602 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.0872594 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.0842057 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.0836023 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.127707 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.0894537 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.0797989 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.108471 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.100206 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.0944274 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.078848 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.0826514 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.0896731 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.134656 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.139191 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.0547109 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.0843337 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.221038 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.0746789 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.0813349 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.0748983 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.0799314 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.130414 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.127195 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.076848 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.0880503 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.11008 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.072192 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.130267 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.136411 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.0743131 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.131511 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.153746 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.155205 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.0772389 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.0499017 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.0576335 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.0789829 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.0511512 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.130048 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.0795794 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.0773851 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.0571002 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.0598796 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.227319 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.129097 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.113591 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.110293 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.10403 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.0764343 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.0789714 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.0854309 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.142117 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.132521 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.0839543 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.0837486 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.128658 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.0822811 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.135095 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.0917943 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.127783 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.229376 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.0773851 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.131938 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.138021 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.130341 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.130267 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.0863086 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.0679253 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.104448 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.0874217 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.0738811 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.138606 +[03/18/2024-15:13:28] [V] [TRT] Conv_160 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.0798149 +[03/18/2024-15:13:28] [V] [TRT] Fastest Tactic: 0x3e7eb35b91b9fa63 Time: 0.0499017 +[03/18/2024-15:13:28] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(97200,1,540,3) *************** +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(97200,32400,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(64800,32400:2,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskFlattenConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(97200,32400,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskFlattenConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_160 (CaskConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Float(8294400,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CudaDepthwiseConvolution) +[03/18/2024-15:13:28] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (FusedConvActConvolution) +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000007ffff Time: 0.161646 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x00000000000affff Time: 0.262107 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x00000000000effff Time: 0.342309 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x00000000000fffff Time: 0.153746 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000019ffff Time: 0.153015 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x00000000001affff Time: 0.338048 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000024ffff Time: 0.211237 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000027ffff Time: 0.166912 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x00000000002dffff Time: 0.153015 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000036ffff Time: 0.186519 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x00000000004cffff Time: 0.18944 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000062ffff Time: 0.182272 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x00000000006effff Time: 0.384 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000077ffff Time: 0.194121 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000086ffff Time: 0.271506 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000089ffff Time: 0.180809 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000097ffff Time: 0.254537 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000098ffff Time: 0.186514 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x00000000009fffff Time: 0.207287 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000a2ffff Time: 0.217527 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000a4ffff Time: 0.4096 +[03/18/2024-15:13:28] [V] [TRT] Fastest Tactic: 0x000000000019ffff Time: 0.153015 +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CudnnConvolution) +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.344078 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.369371 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.390583 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.33749 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.421742 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000006 Time: 0.145408 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.297838 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000039 Time: 0.427447 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000000003a Time: 0.29184 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000000003c Time: 1.21958 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000000003d Time: 0.485376 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000000003e Time: 0.138898 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000070 Time: 0.284087 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000071 Time: 0.284233 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000072 Time: 0.282185 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000074 Time: 1.35212 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000075 Time: 0.400091 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000076 Time: 0.13987 +[03/18/2024-15:13:28] [V] [TRT] Fastest Tactic: 0x000000000000003e Time: 0.138898 +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskGemmConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskFlattenConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskConvolution) +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_scudnn_128x32_relu_small_nn_v1 Tactic: 0xa8609adc4e0ceb90 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa8609adc4e0ceb90 Time: 0.248832 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_scudnn_128x64_relu_xregs_large_nn_v1 Tactic: 0x5deb29b7a8e275f7 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5deb29b7a8e275f7 Time: 0.364251 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_scudnn_128x64_relu_medium_nn_v1 Tactic: 0xf64396b97c889179 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xf64396b97c889179 Time: 0.367031 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_scudnn_winograd_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x94119b4c514b211a Time: 0.126464 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_scudnn_128x128_relu_small_nn_v1 Tactic: 0x503619c69ae500ff +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x503619c69ae500ff Time: 0.690615 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_scudnn_128x128_relu_xregs_large_nn_v1 Tactic: 0x5403ad713f811a18 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5403ad713f811a18 Time: 0.658725 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xcb8a43f748d8a338 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xcb8a43f748d8a338 Time: 0.388055 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x40a12e3938221818 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x40a12e3938221818 Time: 0.451269 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x01cf8ce2da913006 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x01cf8ce2da913006 Time: 0.724992 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xd828f024626fa982 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xd828f024626fa982 Time: 0.583095 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0xa31d27de74b895ff +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa31d27de74b895ff Time: 0.418377 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x9d9fdb5fd9945f64 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x9d9fdb5fd9945f64 Time: 0.191488 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xb0bf940d5e0f9f45 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb0bf940d5e0f9f45 Time: 0.287305 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4727434768e46395 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x4727434768e46395 Time: 0.501216 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_scudnn_128x128_relu_medium_nn_v1 Tactic: 0xf067e6205da31c2e +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xf067e6205da31c2e Time: 0.805888 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x5aa723e0481da855 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5aa723e0481da855 Time: 0.761125 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x8ad32616b1424be4 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x8ad32616b1424be4 Time: 0.28789 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_scudnn_128x64_relu_small_nn_v1 Tactic: 0x3f243c490d502deb +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x3f243c490d502deb Time: 0.520631 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x12dbf7d94ee3696d +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x12dbf7d94ee3696d Time: 0.453339 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x4efce38acc876f5c +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x4efce38acc876f5c Time: 0.764745 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa9366041633a5135 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa9366041633a5135 Time: 0.432713 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nchwkcrs_nchw_tilesize256x128x8_stage3_warpsize4x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xbb8c3889c7eacd30 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xbb8c3889c7eacd30 Time: 0.776046 +[03/18/2024-15:13:28] [V] [TRT] Fastest Tactic: 0x94119b4c514b211a Time: 0.126464 +[03/18/2024-15:13:28] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x94119b4c514b211a +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Float(8294400,1,46080,256) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskFlattenConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskConvolution) +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x7121ec1db3f80c67 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x7121ec1db3f80c67 Time: 0.465627 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x94a7db94ba744c45 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x94a7db94ba744c45 Time: 0.384731 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x32x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0xa6448a1e79f1ca6f +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa6448a1e79f1ca6f Time: 0.275749 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x1da91d865428f237 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x1da91d865428f237 Time: 0.320805 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x0a143be7a52f301a +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0a143be7a52f301a Time: 0.314807 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x32059de4888dfdda +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x32059de4888dfdda Time: 0.188562 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x256x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x3f0c846d6379bc98 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x3f0c846d6379bc98 Time: 1.62436 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x4fd3c46622e98342 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x4fd3c46622e98342 Time: 0.233033 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x62835fce994f06dd +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x62835fce994f06dd Time: 0.404041 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize256x64x8_stage3_warpsize2x2x1_g1_ffma_aligna4_alignc4 Tactic: 0x8014228ec08b4d49 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x8014228ec08b4d49 Time: 0.504101 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x64x8_stage3_warpsize1x4x1_g1_ffma_aligna4_alignc4 Tactic: 0x19b688348f983aa0 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x19b688348f983aa0 Time: 0.445733 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x64x8_stage3_warpsize2x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xf48db81f02eca9ee +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xf48db81f02eca9ee Time: 0.354898 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize32x32x8_stage3_warpsize1x2x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0x5953bec563d26434 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5953bec563d26434 Time: 0.3072 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize64x128x8_stage3_warpsize1x4x1_g1_ffma_t1r3s3_aligna4_alignc4 Tactic: 0xd15dd11d64344e83 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xd15dd11d64344e83 Time: 0.646875 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_f32f32_f32_nhwckrsc_nhwc_tilesize128x16x8_stage3_warpsize4x1x1_g1_ffma_aligna4_alignc4 Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x92ed3100c35fc43e Time: 0.182857 +[03/18/2024-15:13:28] [V] [TRT] Fastest Tactic: 0x92ed3100c35fc43e Time: 0.182857 +[03/18/2024-15:13:28] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x92ed3100c35fc43e +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Float(2073600,1:4,11520,64) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CudaDepthwiseConvolution) +[03/18/2024-15:13:28] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskGemmConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskFlattenConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskConvolution) +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8_t1r3s3 Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x999e005e3b016ea6 Time: 0.508782 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0x65e41d81f093b482 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x65e41d81f093b482 Time: 0.629175 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f32f32_tf32f32_f32_nhwckrsc_nhwc_tilesize128x128x16_stage4_warpsize2x2x1_g1_tensor16x8x8 Tactic: 0xb443c221fcb1565b +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb443c221fcb1565b Time: 0.516389 +[03/18/2024-15:13:28] [V] [TRT] Fastest Tactic: 0x999e005e3b016ea6 Time: 0.508782 +[03/18/2024-15:13:28] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x999e005e3b016ea6 +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CudnnConvolution) +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000000 Time: 0.350062 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000001 Time: 0.291401 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000002 Time: 0.291547 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000004 Time: 1.19676 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000005 Time: 0.557024 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000006 Time: 2.2487 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0000000000000038 Time: 0.311003 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000000003a Time: 0.310565 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000000003c Time: 1.22149 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000000003d Time: 0.582949 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x000000000000003e Time: 2.1899 +[03/18/2024-15:13:28] [V] [TRT] Fastest Tactic: 0x0000000000000001 Time: 0.291401 +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskGemmConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskFlattenConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CudnnConvolution Tactic: 0x0000000000000001 +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (FusedConvActConvolution) +[03/18/2024-15:13:28] [V] [TRT] FusedConvActConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskFlattenConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskConvolution) +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_small_nn_v1 Tactic: 0xea8b68014eaeb55d +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xea8b68014eaeb55d Time: 0.627419 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_medium_nn_v1 Tactic: 0x1e7896ba71ef1635 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x1e7896ba71ef1635 Time: 0.134802 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_fp16x2_hcudnn_winograd_fp16x2_128x128_ldg1_ldg4_relu_tile148t_nt_v1 Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc754debea88ae0b7 Time: 0.0773851 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_large_nn_v1 Tactic: 0x91f7e9c0851ad67c +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x91f7e9c0851ad67c Time: 0.463287 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x128_relu_medium_nn_v1 Tactic: 0x360278e347d63410 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x360278e347d63410 Time: 0.514651 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_small_nn_v1 Tactic: 0xc34b78af38b295a7 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc34b78af38b295a7 Time: 0.126683 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x32_relu_large_nn_v1 Tactic: 0xb837f96ef306f686 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb837f96ef306f686 Time: 0.128654 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_medium_nn_v1 Tactic: 0x4cfee77ea8c324db +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x4cfee77ea8c324db Time: 0.21387 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_large_nn_v1 Tactic: 0x2f735ffbb05a30fd +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x2f735ffbb05a30fd Time: 0.215186 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_fp16x2_hcudnn_fp16x2_128x64_relu_small_nn_v1 Tactic: 0x540fde3a7bee53dc +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x540fde3a7bee53dc Time: 0.211383 +[03/18/2024-15:13:28] [V] [TRT] Fastest Tactic: 0xc754debea88ae0b7 Time: 0.0773851 +[03/18/2024-15:13:28] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0xc754debea88ae0b7 +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:4,11520,64) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskFlattenConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:8,5760,32) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskFlattenConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:8,5760,32) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CudaDepthwiseConvolution) +[03/18/2024-15:13:28] [V] [TRT] CudaDepthwiseConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskGemmConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskGemmConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskFlattenConvolution) +[03/18/2024-15:13:28] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:28] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskConvolution) +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x706f08da35c795a5 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x706f08da35c795a5 Time: 0.117248 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x83ccd4762c1376a1 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x83ccd4762c1376a1 Time: 0.0932571 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x4fc05923455fc266 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x4fc05923455fc266 Time: 0.167058 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xc9cc55109bb4de26 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc9cc55109bb4de26 Time: 0.0945737 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa927df92ac1ef1b8 Time: 0.12288 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd0a3e0c815f7fb5e +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xd0a3e0c815f7fb5e Time: 0.0945623 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x03896956a39a1203 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x03896956a39a1203 Time: 0.150528 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x53be5e206184e6ad +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x53be5e206184e6ad Time: 0.135989 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xc660e51970bc5a3a +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc660e51970bc5a3a Time: 0.135022 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x42a5b8709d0039be +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x42a5b8709d0039be Time: 0.0860891 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x2721a7f18c2700db +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x2721a7f18c2700db Time: 0.156526 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x3b5fa0f2a8fc2410 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x3b5fa0f2a8fc2410 Time: 0.139118 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc9f0a7bec963ba66 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc9f0a7bec963ba66 Time: 0.13803 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x58816bf2e9c36afb +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x58816bf2e9c36afb Time: 0.128439 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0xbeaee7eaad288322 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xbeaee7eaad288322 Time: 0.111323 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb8d86216e1235cda +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb8d86216e1235cda Time: 0.135826 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xb33e57fb3e8a0a56 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb33e57fb3e8a0a56 Time: 0.127781 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xd58ea0bdedb89ead +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xd58ea0bdedb89ead Time: 0.148919 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x544bff7ff9c5d908 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x544bff7ff9c5d908 Time: 0.098736 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0xc2cf926c41243630 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc2cf926c41243630 Time: 0.12939 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0x88971eec55aba850 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x88971eec55aba850 Time: 0.098304 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x7aad3976677d7155 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x7aad3976677d7155 Time: 0.0767863 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x29329b5741ea05f2 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x29329b5741ea05f2 Time: 0.0837394 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x699be152cfb6d6ff +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x699be152cfb6d6ff Time: 0.0792869 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0xce0506e1512285c3 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xce0506e1512285c3 Time: 0.0929646 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x5_medium_nhwc_tn_v1 Tactic: 0x5f31c22ec167f384 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5f31c22ec167f384 Time: 0.0952526 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0x19822de884f42a6a +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x19822de884f42a6a Time: 0.0837486 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0x2eaa2202de9404d6 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x2eaa2202de9404d6 Time: 0.128 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x3_medium_nhwc_tn_v1 Tactic: 0xb85e52e87caf60a2 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb85e52e87caf60a2 Time: 0.148919 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5c2e1c87d85b06f1 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5c2e1c87d85b06f1 Time: 0.136101 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xeb2d2aa4e56bb41c +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xeb2d2aa4e56bb41c Time: 0.0864549 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_256x64_sliced1x2_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x4aed1956bd10a795 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x4aed1956bd10a795 Time: 0.0846263 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0x7163d33a4d8ce8d7 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x7163d33a4d8ce8d7 Time: 0.083968 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x234580e8a194335c +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x234580e8a194335c Time: 0.128073 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x82f8a2214b0b4178 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x82f8a2214b0b4178 Time: 0.0917943 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_large_nhwc_tn_v1 Tactic: 0x59762bd684092b33 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x59762bd684092b33 Time: 0.0797989 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_medium_nhwc_tn_v1 Tactic: 0xa7c9d418a10bce71 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa7c9d418a10bce71 Time: 0.108544 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_small_nhwc_tn_v1 Tactic: 0x1a5ba808ad4cc5a8 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x1a5ba808ad4cc5a8 Time: 0.0989623 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0xf0beb09df9a19f82 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xf0beb09df9a19f82 Time: 0.0944274 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xabd92c9ae596b545 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xabd92c9ae596b545 Time: 0.0792137 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0xca5d3a11fd48f571 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xca5d3a11fd48f571 Time: 0.0827063 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_256x64_sliced1x2_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xd8eb41ee35e76575 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xd8eb41ee35e76575 Time: 0.0895269 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x463794ee4acffd1f +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x463794ee4acffd1f Time: 0.134656 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0xa111596c001b78db +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa111596c001b78db Time: 0.13963 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xf79479a62ea9f901 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xf79479a62ea9f901 Time: 0.0542095 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x59c5c647b4c76593 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x59c5c647b4c76593 Time: 0.0845531 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0xa1a20ea714d420f4 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa1a20ea714d420f4 Time: 0.221184 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x05b6220f243edacd +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x05b6220f243edacd Time: 0.074752 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x30e8a8d7a953e5e9 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x30e8a8d7a953e5e9 Time: 0.0793646 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x263a38afd75e3a43 Time: 0.0729966 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x0866ddee325d07a6 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x0866ddee325d07a6 Time: 0.0791406 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x60c3421152ef8e10 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x60c3421152ef8e10 Time: 0.128439 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdfa020ef435ef810 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xdfa020ef435ef810 Time: 0.125659 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x21b295c0c8f6c95a +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x21b295c0c8f6c95a Time: 0.0758331 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x5013c38f55afa9ba +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5013c38f55afa9ba Time: 0.0871863 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_small_nhwc_tn_v1 Tactic: 0x3369260c04f9ad73 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x3369260c04f9ad73 Time: 0.109056 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5820b3dda403c4d0 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5820b3dda403c4d0 Time: 0.07168 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x048d6d0400f33439 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x048d6d0400f33439 Time: 0.129243 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0xb17d53d15dfbfc9e +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb17d53d15dfbfc9e Time: 0.132681 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xb4bec086187edcfc Time: 0.0738743 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16 Tactic: 0x60da8c7151d91e47 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x60da8c7151d91e47 Time: 0.129902 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_small_nhwc_tn_v1 Tactic: 0xbd6f5e6f24c05c10 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xbd6f5e6f24c05c10 Time: 0.15243 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_sliced1x2_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc8a90ff8898200c3 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc8a90ff8898200c3 Time: 0.1536 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xd1aaad17ca35fbaa +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xd1aaad17ca35fbaa Time: 0.077312 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x3e7eb35b91b9fa63 Time: 0.0495909 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xdce100b9fe609424 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xdce100b9fe609424 Time: 0.0571261 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xe0e3c0e8cf9a2d9e +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xe0e3c0e8cf9a2d9e Time: 0.0778971 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0x834e11ecd4ab9454 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x834e11ecd4ab9454 Time: 0.050656 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xdb0b80f591d1bb6d +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xdb0b80f591d1bb6d Time: 0.128498 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x6426696f872a3b13 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x6426696f872a3b13 Time: 0.078336 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x529f4431bdae94f5 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x529f4431bdae94f5 Time: 0.0768731 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa40cb43c296a36a8 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa40cb43c296a36a8 Time: 0.0562865 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa83b68f30462f971 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa83b68f30462f971 Time: 0.057539 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa9177bbe4e767df8 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xa9177bbe4e767df8 Time: 0.223525 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xc0a02dc6095497cc +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc0a02dc6095497cc Time: 0.127122 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x100c1ad308e08d35 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x100c1ad308e08d35 Time: 0.112366 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x5_large_nhwc_tn_v1 Tactic: 0x8015519605ab9963 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x8015519605ab9963 Time: 0.109001 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_ldg8_relu_exp_stages_64x6_large_nhwc_tn_v1 Tactic: 0x6af049035146c349 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x6af049035146c349 Time: 0.102985 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xbd08239a9317f2fd +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xbd08239a9317f2fd Time: 0.0785554 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x5568fd8a32f4a40f +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x5568fd8a32f4a40f Time: 0.0782629 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xf35e0311fa1cc516 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xf35e0311fa1cc516 Time: 0.084704 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x128_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0xc82f3f06140e3cbb +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc82f3f06140e3cbb Time: 0.141166 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0x2970ae65966d569d +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x2970ae65966d569d Time: 0.131584 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xc9d24bd069159fa8 +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0xc9d24bd069159fa8 Time: 0.083968 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_large_nhwc_tn_v1 Tactic: 0x3197d5044d71e98e +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x3197d5044d71e98e Time: 0.0833646 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:28] [V] [TRT] Tactic: 0x17ebf0c9f418f10a Time: 0.12544 +[03/18/2024-15:13:28] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x4_medium_nhwc_tn_v1 Tactic: 0x196cbc423a9bb69e +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0x196cbc423a9bb69e Time: 0.0821394 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x0e07ff4f4f7c1ac9 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0x0e07ff4f4f7c1ac9 Time: 0.134363 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x4a81ea1e51436a30 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0x4a81ea1e51436a30 Time: 0.09216 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x866e7a5f6401b67f +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0x866e7a5f6401b67f Time: 0.127781 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x256x32_stage3_warpsize2x4x1_g1_tensor16x8x16 Tactic: 0x7005d10718f6c22d +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0x7005d10718f6c22d Time: 0.229669 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x64x32_stage3_warpsize4x1x1_g1_tensor16x8x16 Tactic: 0xa570c55d303796ff +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0xa570c55d303796ff Time: 0.077824 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xafd1e8bf6bd3d638 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0xafd1e8bf6bd3d638 Time: 0.132686 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: ampere_h1688cudnn_256x128_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0x30c0f36d0aeeac6a +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0x30c0f36d0aeeac6a Time: 0.138007 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x32_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x245530c34bd6090f +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0x245530c34bd6090f Time: 0.130633 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x128x64_stage3_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0x57c9a5ff682354a6 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0x57c9a5ff682354a6 Time: 0.13195 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x64x64_stage4_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x31d93dc22d2af081 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0x31d93dc22d2af081 Time: 0.0879909 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xa033e20ae9f412b2 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0xa033e20ae9f412b2 Time: 0.0693882 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_64x64_sliced1x2_ldg8_relu_exp_stages_64x6_small_nhwc_tn_v1 Tactic: 0x24e01e7405cfdfe9 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0x24e01e7405cfdfe9 Time: 0.106423 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_256x64_ldg8_relu_exp_medium_nhwc_tn_v1 Tactic: 0xe4711898bd599c36 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0xe4711898bd599c36 Time: 0.0889509 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x32x64_stage5_warpsize2x2x1_g1_tensor16x8x16 Tactic: 0xe1ff5ad20f5c6bf6 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0xe1ff5ad20f5c6bf6 Time: 0.0754834 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_256x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xdc796d70e228a1d4 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0xdc796d70e228a1d4 Time: 0.141739 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: ampere_h16816cudnn_128x64_ldg8_relu_exp_stages_64x3_small_nhwc_tn_v1 Tactic: 0xc338d2482cee77f8 +[03/18/2024-15:13:29] [V] [TRT] Tactic: 0xc338d2482cee77f8 Time: 0.0816937 +[03/18/2024-15:13:29] [V] [TRT] Fastest Tactic: 0x3e7eb35b91b9fa63 Time: 0.0495909 +[03/18/2024-15:13:29] [V] [TRT] >>>>>>>>>>>>>>> Chose Runner Type: CaskConvolution Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskFlattenConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskFlattenConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_163 (CaskConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(8294400,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(8294400,1,46080,256) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(2073600,1:4,11520,64) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:4,11520,64) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_166 (CaskFlattenConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_166 (CaskConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:8,5760,32) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_166 (CaskFlattenConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_166 (CaskConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:8,5760,32) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_166 (CaskFlattenConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_166 (CaskConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_166 (CaskFlattenConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_166 (CaskConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] =============== Computing costs for +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(8294400,32400,180,1) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(8294400,1,46080,256) long-strided -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(2073600,1:4,11520,64) long-strided -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(8294400,32400,180,1) long-strided -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(4147200,32400:2,180,1) long-strided -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(2073600,1:4,11520,64) long-strided -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_169 (CaskFlattenConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_169 (CaskConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:8,5760,32) long-strided -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_169 (CaskFlattenConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_169 (CaskConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(1036800,1:8,5760,32) long-strided -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(2073600,32400,180,1) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(2073600,1,11520,64) -> Float(64800,1,360,2) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Float(518400,1:4,2880,16) -> Float(32400,1:4,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(2073600,32400,180,1) -> Half(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(1036800,32400:2,180,1) -> Half(32400,32400:2,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(518400,1:4,2880,16) -> Half(32400,1:4,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_169 (CaskFlattenConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_169 (CaskConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Float(64800,32400,180,1) *************** +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_169 (CaskFlattenConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskFlattenConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] --------------- Timing Runner: Conv_169 (CaskConvolution) +[03/18/2024-15:13:29] [V] [TRT] CaskConvolution has no valid tactics for this config, skipping +[03/18/2024-15:13:29] [V] [TRT] *************** Autotuning format combination: Half(259200,1:8,1440,8) -> Half(32400,1:8,180,1) *************** +[03/18/2024-15:13:29] [I] [TRT] [GraphReduction] The approximate region cut reduction algorithm is called. +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Input Tensor 0 to Conv_15 + Relu_16 (input) from Half(8294400,32400,180,1) to Half(1036800,1:8,5760,32) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_64 (reg_0) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_67 (height_0) from Half(32400,1:8,180,1) to Half(32400,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_70 (dim_0) from Half(32400,1:8,180,1) to Half(97200,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_73 (rot_0) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_76 (vel_0) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_79 (hm_0) from Half(32400,1:8,180,1) to Half(32400,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_82 (reg_1) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_85 (height_1) from Half(32400,1:8,180,1) to Half(32400,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_88 (dim_1) from Half(32400,1:8,180,1) to Half(97200,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_91 (rot_1) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_94 (vel_1) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_97 (hm_1) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_100 (reg_2) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_103 (height_2) from Half(32400,1:8,180,1) to Half(32400,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_106 (dim_2) from Half(32400,1:8,180,1) to Half(97200,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_109 (rot_2) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_112 (vel_2) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_115 (hm_2) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_118 (reg_3) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_121 (height_3) from Half(32400,1:8,180,1) to Half(32400,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_124 (dim_3) from Half(32400,1:8,180,1) to Half(97200,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_127 (rot_3) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_130 (vel_3) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_133 (hm_3) from Half(32400,1:8,180,1) to Half(32400,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_136 (reg_4) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_139 (height_4) from Half(32400,1:8,180,1) to Half(32400,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_142 (dim_4) from Half(32400,1:8,180,1) to Half(97200,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_145 (rot_4) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_148 (vel_4) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_151 (hm_4) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_154 (reg_5) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_157 (height_5) from Half(32400,1:8,180,1) to Half(32400,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_160 (dim_5) from Half(32400,1:8,180,1) to Half(97200,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_163 (rot_5) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_166 (vel_5) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Adding reformat layer: Reformatted Output Tensor 0 to Conv_169 (hm_5) from Half(32400,1:8,180,1) to Half(64800,32400,180,1) +[03/18/2024-15:13:29] [V] [TRT] Formats and tactics selection completed in 47.7991 seconds. +[03/18/2024-15:13:29] [V] [TRT] After reformat layers: 93 layers +[03/18/2024-15:13:29] [V] [TRT] Total number of blocks in pre-optimized block assignment: 57 +[03/18/2024-15:13:29] [I] [TRT] Total Activation Memory: 4591501312 +[03/18/2024-15:13:29] [I] [TRT] Detected 1 inputs and 36 output network tensors. +[03/18/2024-15:13:29] [V] [TRT] Conv_15 + Relu_16 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:29] [V] [TRT] Conv_17 + Relu_18 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:29] [V] [TRT] Conv_19 + Relu_20 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:29] [V] [TRT] Conv_21 + Relu_22 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:29] [V] [TRT] Conv_23 + Relu_24 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:29] [V] [TRT] Conv_25 + Relu_26 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:29] [V] [TRT] Conv_27 + Relu_28 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_interior_nhwc_tn_v1 Tactic: 0xfa5a19eb8211e798 +[03/18/2024-15:13:29] [V] [TRT] Conv_44 + Relu_45 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x17ebf0c9f418f10a +[03/18/2024-15:13:29] [V] [TRT] Conv_46 + Relu_47 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:29] [V] [TRT] Conv_48 + Relu_49 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:29] [V] [TRT] Conv_50 + Relu_51 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:29] [V] [TRT] Conv_52 + Relu_53 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:29] [V] [TRT] Conv_54 + Relu_55 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS Tactic: 0x263a38afd75e3a43 +[03/18/2024-15:13:29] [V] [TRT] ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set Tactic Name: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_strided Tactic: 0xdec24e75875e331b +[03/18/2024-15:13:29] [V] [TRT] Conv_60 + Relu_61 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3 Tactic: 0xb4bec086187edcfc +[03/18/2024-15:13:29] [V] [TRT] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:29] [V] [TRT] Conv_64 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_67 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_70 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_73 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_76 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_79 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_82 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_85 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:29] [V] [TRT] Conv_88 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_91 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_94 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_97 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_100 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_103 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_106 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_109 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:29] [V] [TRT] Conv_112 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_115 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_118 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_121 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_124 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_127 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_130 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_133 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:29] [V] [TRT] Conv_136 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_139 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_142 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_145 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_148 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_151 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_154 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_157 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set Tactic Name: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1 Tactic: 0xa927df92ac1ef1b8 +[03/18/2024-15:13:29] [V] [TRT] Conv_160 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_163 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_166 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Conv_169 Set Tactic Name: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3 Tactic: 0x3e7eb35b91b9fa63 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_15 + Relu_16 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_17 + Relu_18 Host Persistent: 4224 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_19 + Relu_20 Host Persistent: 4224 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_21 + Relu_22 Host Persistent: 4224 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_23 + Relu_24 Host Persistent: 4224 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_25 + Relu_26 Host Persistent: 4224 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_27 + Relu_28 Host Persistent: 3200 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_44 + Relu_45 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_46 + Relu_47 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_48 + Relu_49 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_50 + Relu_51 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_52 + Relu_53 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_54 + Relu_55 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: ConvTranspose_56 + BatchNormalization_57 + Relu_58 Host Persistent: 2688 Device Persistent: 136704 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_60 + Relu_61 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Host Persistent: 4224 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_64 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_67 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_70 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_73 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_76 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_79 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_82 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_85 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 Host Persistent: 4224 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_88 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_91 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_94 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_97 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_100 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_103 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_106 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_109 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 Host Persistent: 4224 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_112 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_115 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_118 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_121 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_124 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_127 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_130 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_133 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 Host Persistent: 4224 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_136 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_139 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_142 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_145 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_148 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_151 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_154 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_157 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Host Persistent: 4224 Device Persistent: 194560 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_160 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_163 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_166 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Layer: Conv_169 Host Persistent: 3264 Device Persistent: 0 Scratch Memory: 0 +[03/18/2024-15:13:29] [V] [TRT] Skipped printing memory information for 37 layers with 0 memory size i.e. Host Persistent + Device Persistent + Scratch Memory == 0. +[03/18/2024-15:13:29] [I] [TRT] Total Host Persistent Memory: 191744 +[03/18/2024-15:13:29] [I] [TRT] Total Device Persistent Memory: 2276864 +[03/18/2024-15:13:29] [I] [TRT] Total Scratch Memory: 0 +[03/18/2024-15:13:29] [I] [TRT] [MemUsageStats] Peak memory usage of TRT CPU/GPU memory allocators: CPU 18 MiB, GPU 643 MiB +[03/18/2024-15:13:29] [I] [TRT] [BlockAssignment] Started assigning block shifts. This will take 56 steps to complete. +[03/18/2024-15:13:29] [I] [TRT] [BlockAssignment] Algorithm ShiftNTopDown took 0.184407ms to assign 3 blocks to 56 nodes requiring 49766400 bytes. +[03/18/2024-15:13:29] [V] [TRT] Total number of blocks in optimized block assignment: 3 +[03/18/2024-15:13:29] [I] [TRT] Total Activation Memory: 49766400 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_15 + Relu_16 Set kernel index: 0 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_17 + Relu_18 Set kernel index: 1 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_19 + Relu_20 Set kernel index: 1 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_21 + Relu_22 Set kernel index: 1 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_23 + Relu_24 Set kernel index: 1 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_25 + Relu_26 Set kernel index: 1 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_27 + Relu_28 Set kernel index: 2 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_44 + Relu_45 Set kernel index: 3 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_46 + Relu_47 Set kernel index: 0 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_48 + Relu_49 Set kernel index: 0 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_50 + Relu_51 Set kernel index: 0 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_52 + Relu_53 Set kernel index: 0 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_54 + Relu_55 Set kernel index: 0 +[03/18/2024-15:13:29] [V] [TRT] Finalize: ConvTranspose_56 + BatchNormalization_57 + Relu_58 Set kernel index: 4 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_60 + Relu_61 Set kernel index: 5 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 Set kernel index: 1 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_64 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_67 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_70 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_73 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_76 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_79 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_82 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_85 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 Set kernel index: 1 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_88 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_91 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_94 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_97 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_100 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_103 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_106 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_109 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 Set kernel index: 1 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_112 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_115 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_118 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_121 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_124 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_127 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_130 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_133 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 Set kernel index: 1 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_136 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_139 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_142 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_145 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_148 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_151 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_154 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_157 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 Set kernel index: 1 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_160 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_163 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_166 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Finalize: Conv_169 Set kernel index: 6 +[03/18/2024-15:13:29] [V] [TRT] Total number of generated kernels selected for the engine: 7 +[03/18/2024-15:13:29] [V] [TRT] Kernel: 0 CASK_STATIC +[03/18/2024-15:13:29] [V] [TRT] Kernel: 1 CASK_STATIC +[03/18/2024-15:13:29] [V] [TRT] Kernel: 2 CASK_STATIC +[03/18/2024-15:13:29] [V] [TRT] Kernel: 3 CASK_STATIC +[03/18/2024-15:13:29] [V] [TRT] Kernel: 4 CASK_STATIC +[03/18/2024-15:13:29] [V] [TRT] Kernel: 5 CASK_STATIC +[03/18/2024-15:13:29] [V] [TRT] Kernel: 6 CASK_STATIC +[03/18/2024-15:13:29] [V] [TRT] Disabling unused tactic source: CUDNN +[03/18/2024-15:13:29] [V] [TRT] Disabling unused tactic source: CUBLAS, CUBLAS_LT +[03/18/2024-15:13:29] [V] [TRT] Disabling unused tactic source: JIT_CONVOLUTIONS +[03/18/2024-15:13:29] [V] [TRT] Engine generation completed in 48.4321 seconds. +[03/18/2024-15:13:29] [W] [TRT] TensorRT encountered issues when converting weights between types and that could affect accuracy. +[03/18/2024-15:13:29] [W] [TRT] If this is not the desired behavior, please modify the weights or retrain with regularization to adjust the magnitude of the weights. +[03/18/2024-15:13:29] [W] [TRT] Check verbose logs for the list of affected weights. +[03/18/2024-15:13:29] [W] [TRT] - 28 weights are affected by this issue: Detected subnormal FP16 values. +[03/18/2024-15:13:29] [V] [TRT] List of affected weights: ConvTranspose_56 + BatchNormalization_57 + Relu_58.weight, Conv_100.weight, Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132.weight, Conv_124.weight, Conv_127.weight, Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156.weight, Conv_145.weight, Conv_15 + Relu_16.weight, Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168.weight, Conv_163.weight, Conv_17 + Relu_18.weight, Conv_19 + Relu_20.weight, Conv_21 + Relu_22.weight, Conv_23 + Relu_24.weight, Conv_25 + Relu_26.weight, Conv_27 + Relu_28.weight, Conv_44 + Relu_45.weight, Conv_46 + Relu_47.weight, Conv_48 + Relu_49.weight, Conv_50 + Relu_51.weight, Conv_52 + Relu_53.weight, Conv_54 + Relu_55.weight, Conv_60 + Relu_61.weight, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84.bias, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84.weight, Conv_73.weight, Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108.weight, Conv_88.weight +[03/18/2024-15:13:29] [W] [TRT] - 17 weights are affected by this issue: Detected values less than smallest positive FP16 subnormal value and converted them to the FP16 minimum subnormalized value. +[03/18/2024-15:13:29] [V] [TRT] List of affected weights: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132.weight, Conv_112.bias, Conv_130.bias, Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156.weight, Conv_148.bias, Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168.weight, Conv_166.bias, Conv_21 + Relu_22.weight, Conv_23 + Relu_24.weight, Conv_46 + Relu_47.weight, Conv_50 + Relu_51.weight, Conv_52 + Relu_53.weight, Conv_60 + Relu_61.weight, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84.weight, Conv_76.bias, Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108.weight, Conv_94.bias +[03/18/2024-15:13:29] [V] [TRT] Deleting timing cache: 811 entries, served 4617 hits since creation. +[03/18/2024-15:13:29] [V] [TRT] Engine Layer Information: +Layer(Reformat): Reformatting CopyNode for Input Tensor 0 to Conv_15 + Relu_16, Tactic: 0x00000000000003ea, input (Half[1,256,180,180]) -> Reformatted Input Tensor 0 to Conv_15 + Relu_16 (Half[1,256:8,180,180]) +Layer(CaskConvolution): Conv_15 + Relu_16, Tactic: 0x263a38afd75e3a43, Reformatted Input Tensor 0 to Conv_15 + Relu_16 (Half[1,256:8,180,180]) -> input.12 (Half[1,128:8,180,180]) +Layer(CaskConvolution): Conv_17 + Relu_18, Tactic: 0xa927df92ac1ef1b8, input.12 (Half[1,128:8,180,180]) -> input.24 (Half[1,128:8,180,180]) +Layer(CaskConvolution): Conv_19 + Relu_20, Tactic: 0xa927df92ac1ef1b8, input.24 (Half[1,128:8,180,180]) -> input.36 (Half[1,128:8,180,180]) +Layer(CaskConvolution): Conv_21 + Relu_22, Tactic: 0xa927df92ac1ef1b8, input.36 (Half[1,128:8,180,180]) -> input.48 (Half[1,128:8,180,180]) +Layer(CaskConvolution): Conv_23 + Relu_24, Tactic: 0xa927df92ac1ef1b8, input.48 (Half[1,128:8,180,180]) -> input.60 (Half[1,128:8,180,180]) +Layer(CaskConvolution): Conv_25 + Relu_26, Tactic: 0xa927df92ac1ef1b8, input.60 (Half[1,128:8,180,180]) -> input.72 (Half[1,128:8,180,180]) +Layer(CaskConvolution): Conv_27 + Relu_28, Tactic: 0xfa5a19eb8211e798, input.72 (Half[1,128:8,180,180]) -> input.164 (Half[1,256:8,180,180]) +Layer(CaskConvolution): Conv_44 + Relu_45, Tactic: 0x17ebf0c9f418f10a, input.72 (Half[1,128:8,180,180]) -> input.96 (Half[1,256:8,90,90]) +Layer(CaskConvolution): Conv_46 + Relu_47, Tactic: 0x263a38afd75e3a43, input.96 (Half[1,256:8,90,90]) -> input.108 (Half[1,256:8,90,90]) +Layer(CaskConvolution): Conv_48 + Relu_49, Tactic: 0x263a38afd75e3a43, input.108 (Half[1,256:8,90,90]) -> input.120 (Half[1,256:8,90,90]) +Layer(CaskConvolution): Conv_50 + Relu_51, Tactic: 0x263a38afd75e3a43, input.120 (Half[1,256:8,90,90]) -> input.132 (Half[1,256:8,90,90]) +Layer(CaskConvolution): Conv_52 + Relu_53, Tactic: 0x263a38afd75e3a43, input.132 (Half[1,256:8,90,90]) -> input.144 (Half[1,256:8,90,90]) +Layer(CaskConvolution): Conv_54 + Relu_55, Tactic: 0x263a38afd75e3a43, input.144 (Half[1,256:8,90,90]) -> onnx::ConvTranspose_644 (Half[1,256:8,90,90]) +Layer(CaskDeconvolutionV2): ConvTranspose_56 + BatchNormalization_57 + Relu_58, Tactic: 0xdec24e75875e331b, onnx::ConvTranspose_644 (Half[1,256:8,90,90]) -> input.164 (Half[1,256:8,180,180]) +Layer(CaskConvolution): Conv_60 + Relu_61, Tactic: 0xb4bec086187edcfc, input.164 (Half[1,512:8,180,180]) -> onnx::Conv_651 (Half[1,64:8,180,180]) +Layer(CaskConvolution): Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, Tactic: 0xa927df92ac1ef1b8, onnx::Conv_651 (Half[1,64:8,180,180]) -> Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (Half[1,512:8,180,180]) +Layer(CaskConvolution): Conv_64, Tactic: 0x3e7eb35b91b9fa63, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_64 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_64, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_64 (Half[1,2:8,180,180]) -> reg_0 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_67, Tactic: 0x3e7eb35b91b9fa63, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_67 (Half[1,1:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_67, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_67 (Half[1,1:8,180,180]) -> height_0 (Half[1,1,180,180]) +Layer(CaskConvolution): Conv_70, Tactic: 0x3e7eb35b91b9fa63, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_70 (Half[1,3:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_70, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_70 (Half[1,3:8,180,180]) -> dim_0 (Half[1,3,180,180]) +Layer(CaskConvolution): Conv_73, Tactic: 0x3e7eb35b91b9fa63, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_73 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_73, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_73 (Half[1,2:8,180,180]) -> rot_0 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_76, Tactic: 0x3e7eb35b91b9fa63, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_76 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_76, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_76 (Half[1,2:8,180,180]) -> vel_0 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_79, Tactic: 0x3e7eb35b91b9fa63, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_79 (Half[1,1:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_79, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_79 (Half[1,1:8,180,180]) -> hm_0 (Half[1,1,180,180]) +Layer(CaskConvolution): Conv_82, Tactic: 0x3e7eb35b91b9fa63, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_82 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_82, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_82 (Half[1,2:8,180,180]) -> reg_1 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_85, Tactic: 0x3e7eb35b91b9fa63, Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_85 (Half[1,1:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_85, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_85 (Half[1,1:8,180,180]) -> height_1 (Half[1,1,180,180]) +Layer(CaskConvolution): Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, Tactic: 0xa927df92ac1ef1b8, onnx::Conv_651 (Half[1,64:8,180,180]) -> Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (Half[1,512:8,180,180]) +Layer(CaskConvolution): Conv_88, Tactic: 0x3e7eb35b91b9fa63, Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_88 (Half[1,3:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_88, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_88 (Half[1,3:8,180,180]) -> dim_1 (Half[1,3,180,180]) +Layer(CaskConvolution): Conv_91, Tactic: 0x3e7eb35b91b9fa63, Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_91 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_91, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_91 (Half[1,2:8,180,180]) -> rot_1 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_94, Tactic: 0x3e7eb35b91b9fa63, Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_94 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_94, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_94 (Half[1,2:8,180,180]) -> vel_1 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_97, Tactic: 0x3e7eb35b91b9fa63, Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_97 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_97, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_97 (Half[1,2:8,180,180]) -> hm_1 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_100, Tactic: 0x3e7eb35b91b9fa63, Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_100 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_100, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_100 (Half[1,2:8,180,180]) -> reg_2 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_103, Tactic: 0x3e7eb35b91b9fa63, Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_103 (Half[1,1:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_103, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_103 (Half[1,1:8,180,180]) -> height_2 (Half[1,1,180,180]) +Layer(CaskConvolution): Conv_106, Tactic: 0x3e7eb35b91b9fa63, Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_106 (Half[1,3:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_106, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_106 (Half[1,3:8,180,180]) -> dim_2 (Half[1,3,180,180]) +Layer(CaskConvolution): Conv_109, Tactic: 0x3e7eb35b91b9fa63, Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_109 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_109, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_109 (Half[1,2:8,180,180]) -> rot_2 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, Tactic: 0xa927df92ac1ef1b8, onnx::Conv_651 (Half[1,64:8,180,180]) -> Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (Half[1,512:8,180,180]) +Layer(CaskConvolution): Conv_112, Tactic: 0x3e7eb35b91b9fa63, Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_112 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_112, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_112 (Half[1,2:8,180,180]) -> vel_2 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_115, Tactic: 0x3e7eb35b91b9fa63, Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_115 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_115, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_115 (Half[1,2:8,180,180]) -> hm_2 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_118, Tactic: 0x3e7eb35b91b9fa63, Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_118 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_118, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_118 (Half[1,2:8,180,180]) -> reg_3 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_121, Tactic: 0x3e7eb35b91b9fa63, Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_121 (Half[1,1:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_121, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_121 (Half[1,1:8,180,180]) -> height_3 (Half[1,1,180,180]) +Layer(CaskConvolution): Conv_124, Tactic: 0x3e7eb35b91b9fa63, Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_124 (Half[1,3:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_124, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_124 (Half[1,3:8,180,180]) -> dim_3 (Half[1,3,180,180]) +Layer(CaskConvolution): Conv_127, Tactic: 0x3e7eb35b91b9fa63, Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_127 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_127, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_127 (Half[1,2:8,180,180]) -> rot_3 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_130, Tactic: 0x3e7eb35b91b9fa63, Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_130 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_130, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_130 (Half[1,2:8,180,180]) -> vel_3 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_133, Tactic: 0x3e7eb35b91b9fa63, Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_133 (Half[1,1:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_133, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_133 (Half[1,1:8,180,180]) -> hm_3 (Half[1,1,180,180]) +Layer(CaskConvolution): Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, Tactic: 0xa927df92ac1ef1b8, onnx::Conv_651 (Half[1,64:8,180,180]) -> Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (Half[1,512:8,180,180]) +Layer(CaskConvolution): Conv_136, Tactic: 0x3e7eb35b91b9fa63, Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_136 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_136, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_136 (Half[1,2:8,180,180]) -> reg_4 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_139, Tactic: 0x3e7eb35b91b9fa63, Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_139 (Half[1,1:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_139, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_139 (Half[1,1:8,180,180]) -> height_4 (Half[1,1,180,180]) +Layer(CaskConvolution): Conv_142, Tactic: 0x3e7eb35b91b9fa63, Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_142 (Half[1,3:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_142, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_142 (Half[1,3:8,180,180]) -> dim_4 (Half[1,3,180,180]) +Layer(CaskConvolution): Conv_145, Tactic: 0x3e7eb35b91b9fa63, Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_145 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_145, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_145 (Half[1,2:8,180,180]) -> rot_4 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_148, Tactic: 0x3e7eb35b91b9fa63, Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_148 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_148, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_148 (Half[1,2:8,180,180]) -> vel_4 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_151, Tactic: 0x3e7eb35b91b9fa63, Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_151 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_151, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_151 (Half[1,2:8,180,180]) -> hm_4 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_154, Tactic: 0x3e7eb35b91b9fa63, Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_154 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_154, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_154 (Half[1,2:8,180,180]) -> reg_5 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_157, Tactic: 0x3e7eb35b91b9fa63, Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_157 (Half[1,1:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_157, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_157 (Half[1,1:8,180,180]) -> height_5 (Half[1,1,180,180]) +Layer(CaskConvolution): Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168, Tactic: 0xa927df92ac1ef1b8, onnx::Conv_651 (Half[1,64:8,180,180]) -> Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (Half[1,256:8,180,180]) +Layer(CaskConvolution): Conv_160, Tactic: 0x3e7eb35b91b9fa63, Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_160 (Half[1,3:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_160, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_160 (Half[1,3:8,180,180]) -> dim_5 (Half[1,3,180,180]) +Layer(CaskConvolution): Conv_163, Tactic: 0x3e7eb35b91b9fa63, Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_163 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_163, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_163 (Half[1,2:8,180,180]) -> rot_5 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_166, Tactic: 0x3e7eb35b91b9fa63, Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_166 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_166, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_166 (Half[1,2:8,180,180]) -> vel_5 (Half[1,2,180,180]) +Layer(CaskConvolution): Conv_169, Tactic: 0x3e7eb35b91b9fa63, Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 (Half[1,64:8,180,180]) -> Reformatted Output Tensor 0 to Conv_169 (Half[1,2:8,180,180]) +Layer(Reformat): Reformatting CopyNode for Output Tensor 0 to Conv_169, Tactic: 0x0000000000000000, Reformatted Output Tensor 0 to Conv_169 (Half[1,2:8,180,180]) -> hm_5 (Half[1,2,180,180]) +[03/18/2024-15:13:29] [I] [TRT] [MemUsageChange] TensorRT-managed allocation in building engine: CPU +12, GPU +15, now: CPU 12, GPU 15 (MiB) +[03/18/2024-15:13:29] [I] Engine built in 49.9871 sec. +[03/18/2024-15:13:29] [I] [TRT] Loaded engine size: 12 MiB +[03/18/2024-15:13:29] [V] [TRT] Deserialization required 3883 microseconds. +[03/18/2024-15:13:29] [I] [TRT] [MemUsageChange] TensorRT-managed allocation in engine deserialization: CPU +0, GPU +14, now: CPU 0, GPU 14 (MiB) +[03/18/2024-15:13:29] [I] Engine deserialized in 0.00406646 sec. +[03/18/2024-15:13:29] [V] [TRT] Total per-runner device persistent memory is 2276864 +[03/18/2024-15:13:29] [V] [TRT] Total per-runner host persistent memory is 191744 +[03/18/2024-15:13:29] [V] [TRT] Allocated activation device memory of size 49766400 +[03/18/2024-15:13:29] [I] [TRT] [MemUsageChange] TensorRT-managed allocation in IExecutionContext creation: CPU +0, GPU +49, now: CPU 0, GPU 63 (MiB) +[03/18/2024-15:13:29] [V] [TRT] CUDA lazy loading is enabled. +[03/18/2024-15:13:29] [I] Setting persistentCacheLimit to 0 bytes. +[03/18/2024-15:13:29] [V] Using enqueueV3. +[03/18/2024-15:13:29] [I] Using random values for input input +[03/18/2024-15:13:29] [I] Created input binding for input with dimensions 1x256x180x180 +[03/18/2024-15:13:29] [I] Using random values for output reg_0 +[03/18/2024-15:13:29] [I] Created output binding for reg_0 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output height_0 +[03/18/2024-15:13:29] [I] Created output binding for height_0 with dimensions 1x1x180x180 +[03/18/2024-15:13:29] [I] Using random values for output dim_0 +[03/18/2024-15:13:29] [I] Created output binding for dim_0 with dimensions 1x3x180x180 +[03/18/2024-15:13:29] [I] Using random values for output rot_0 +[03/18/2024-15:13:29] [I] Created output binding for rot_0 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output vel_0 +[03/18/2024-15:13:29] [I] Created output binding for vel_0 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output hm_0 +[03/18/2024-15:13:29] [I] Created output binding for hm_0 with dimensions 1x1x180x180 +[03/18/2024-15:13:29] [I] Using random values for output reg_1 +[03/18/2024-15:13:29] [I] Created output binding for reg_1 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output height_1 +[03/18/2024-15:13:29] [I] Created output binding for height_1 with dimensions 1x1x180x180 +[03/18/2024-15:13:29] [I] Using random values for output dim_1 +[03/18/2024-15:13:29] [I] Created output binding for dim_1 with dimensions 1x3x180x180 +[03/18/2024-15:13:29] [I] Using random values for output rot_1 +[03/18/2024-15:13:29] [I] Created output binding for rot_1 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output vel_1 +[03/18/2024-15:13:29] [I] Created output binding for vel_1 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output hm_1 +[03/18/2024-15:13:29] [I] Created output binding for hm_1 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output reg_2 +[03/18/2024-15:13:29] [I] Created output binding for reg_2 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output height_2 +[03/18/2024-15:13:29] [I] Created output binding for height_2 with dimensions 1x1x180x180 +[03/18/2024-15:13:29] [I] Using random values for output dim_2 +[03/18/2024-15:13:29] [I] Created output binding for dim_2 with dimensions 1x3x180x180 +[03/18/2024-15:13:29] [I] Using random values for output rot_2 +[03/18/2024-15:13:29] [I] Created output binding for rot_2 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output vel_2 +[03/18/2024-15:13:29] [I] Created output binding for vel_2 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output hm_2 +[03/18/2024-15:13:29] [I] Created output binding for hm_2 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output reg_3 +[03/18/2024-15:13:29] [I] Created output binding for reg_3 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output height_3 +[03/18/2024-15:13:29] [I] Created output binding for height_3 with dimensions 1x1x180x180 +[03/18/2024-15:13:29] [I] Using random values for output dim_3 +[03/18/2024-15:13:29] [I] Created output binding for dim_3 with dimensions 1x3x180x180 +[03/18/2024-15:13:29] [I] Using random values for output rot_3 +[03/18/2024-15:13:29] [I] Created output binding for rot_3 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output vel_3 +[03/18/2024-15:13:29] [I] Created output binding for vel_3 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output hm_3 +[03/18/2024-15:13:29] [I] Created output binding for hm_3 with dimensions 1x1x180x180 +[03/18/2024-15:13:29] [I] Using random values for output reg_4 +[03/18/2024-15:13:29] [I] Created output binding for reg_4 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output height_4 +[03/18/2024-15:13:29] [I] Created output binding for height_4 with dimensions 1x1x180x180 +[03/18/2024-15:13:29] [I] Using random values for output dim_4 +[03/18/2024-15:13:29] [I] Created output binding for dim_4 with dimensions 1x3x180x180 +[03/18/2024-15:13:29] [I] Using random values for output rot_4 +[03/18/2024-15:13:29] [I] Created output binding for rot_4 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output vel_4 +[03/18/2024-15:13:29] [I] Created output binding for vel_4 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output hm_4 +[03/18/2024-15:13:29] [I] Created output binding for hm_4 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output reg_5 +[03/18/2024-15:13:29] [I] Created output binding for reg_5 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output height_5 +[03/18/2024-15:13:29] [I] Created output binding for height_5 with dimensions 1x1x180x180 +[03/18/2024-15:13:29] [I] Using random values for output dim_5 +[03/18/2024-15:13:29] [I] Created output binding for dim_5 with dimensions 1x3x180x180 +[03/18/2024-15:13:29] [I] Using random values for output rot_5 +[03/18/2024-15:13:29] [I] Created output binding for rot_5 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output vel_5 +[03/18/2024-15:13:29] [I] Created output binding for vel_5 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Using random values for output hm_5 +[03/18/2024-15:13:29] [I] Created output binding for hm_5 with dimensions 1x2x180x180 +[03/18/2024-15:13:29] [I] Layer Information: +[03/18/2024-15:13:29] [I] Layers: +Name: Reformatting CopyNode for Input Tensor 0 to Conv_15 + Relu_16, LayerType: Reformat, Inputs: [ { Name: input, Location: Device, Dimensions: [1,256,180,180], Format/Datatype: Row major linear FP16 format }], Outputs: [ { Name: Reformatted Input Tensor 0 to Conv_15 + Relu_16, Location: Device, Dimensions: [1,256,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x00000000000003ea +Name: Conv_15 + Relu_16, LayerType: CaskConvolution, Inputs: [ { Name: Reformatted Input Tensor 0 to Conv_15 + Relu_16, Location: Device, Dimensions: [1,256,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.12, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 128, Groups: 1, Weights: {"Type": "Half", "Count": 294912}, Bias: {"Type": "Half", "Count": 128}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS, TacticValue: 0x263a38afd75e3a43 +Name: Conv_17 + Relu_18, LayerType: CaskConvolution, Inputs: [ { Name: input.12, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.24, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 128, Groups: 1, Weights: {"Type": "Half", "Count": 147456}, Bias: {"Type": "Half", "Count": 128}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1, TacticValue: 0xa927df92ac1ef1b8 +Name: Conv_19 + Relu_20, LayerType: CaskConvolution, Inputs: [ { Name: input.24, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.36, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 128, Groups: 1, Weights: {"Type": "Half", "Count": 147456}, Bias: {"Type": "Half", "Count": 128}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1, TacticValue: 0xa927df92ac1ef1b8 +Name: Conv_21 + Relu_22, LayerType: CaskConvolution, Inputs: [ { Name: input.36, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.48, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 128, Groups: 1, Weights: {"Type": "Half", "Count": 147456}, Bias: {"Type": "Half", "Count": 128}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1, TacticValue: 0xa927df92ac1ef1b8 +Name: Conv_23 + Relu_24, LayerType: CaskConvolution, Inputs: [ { Name: input.48, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.60, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 128, Groups: 1, Weights: {"Type": "Half", "Count": 147456}, Bias: {"Type": "Half", "Count": 128}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1, TacticValue: 0xa927df92ac1ef1b8 +Name: Conv_25 + Relu_26, LayerType: CaskConvolution, Inputs: [ { Name: input.60, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.72, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 128, Groups: 1, Weights: {"Type": "Half", "Count": 147456}, Bias: {"Type": "Half", "Count": 128}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1, TacticValue: 0xa927df92ac1ef1b8 +Name: Conv_27 + Relu_28, LayerType: CaskConvolution, Inputs: [ { Name: input.72, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.164, Location: Device, Dimensions: [1,256,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [1,1], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [0,0], PostPadding: [0,0], Stride: [1,1], Dilation: [1,1], OutMaps: 256, Groups: 1, Weights: {"Type": "Half", "Count": 32768}, Bias: {"Type": "Half", "Count": 256}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_interior_nhwc_tn_v1, TacticValue: 0xfa5a19eb8211e798 +Name: Conv_44 + Relu_45, LayerType: CaskConvolution, Inputs: [ { Name: input.72, Location: Device, Dimensions: [1,128,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.96, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [2,2], Dilation: [1,1], OutMaps: 256, Groups: 1, Weights: {"Type": "Half", "Count": 294912}, Bias: {"Type": "Half", "Count": 256}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize64x128x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x17ebf0c9f418f10a +Name: Conv_46 + Relu_47, LayerType: CaskConvolution, Inputs: [ { Name: input.96, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.108, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 256, Groups: 1, Weights: {"Type": "Half", "Count": 589824}, Bias: {"Type": "Half", "Count": 256}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS, TacticValue: 0x263a38afd75e3a43 +Name: Conv_48 + Relu_49, LayerType: CaskConvolution, Inputs: [ { Name: input.108, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.120, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 256, Groups: 1, Weights: {"Type": "Half", "Count": 589824}, Bias: {"Type": "Half", "Count": 256}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS, TacticValue: 0x263a38afd75e3a43 +Name: Conv_50 + Relu_51, LayerType: CaskConvolution, Inputs: [ { Name: input.120, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.132, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 256, Groups: 1, Weights: {"Type": "Half", "Count": 589824}, Bias: {"Type": "Half", "Count": 256}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS, TacticValue: 0x263a38afd75e3a43 +Name: Conv_52 + Relu_53, LayerType: CaskConvolution, Inputs: [ { Name: input.132, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.144, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 256, Groups: 1, Weights: {"Type": "Half", "Count": 589824}, Bias: {"Type": "Half", "Count": 256}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS, TacticValue: 0x263a38afd75e3a43 +Name: Conv_54 + Relu_55, LayerType: CaskConvolution, Inputs: [ { Name: input.144, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: onnx::ConvTranspose_644, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 256, Groups: 1, Weights: {"Type": "Half", "Count": 589824}, Bias: {"Type": "Half", "Count": 256}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x64_stage3_warpsize2x2x1_g1_tensor16x8x16_t1r3s3_aACCESS, TacticValue: 0x263a38afd75e3a43 +Name: ConvTranspose_56 + BatchNormalization_57 + Relu_58, LayerType: CaskDeconvolutionV2, Inputs: [ { Name: onnx::ConvTranspose_644, Location: Device, Dimensions: [1,256,90,90], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: input.164, Location: Device, Dimensions: [1,256,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], HasBias: 1, HasReLU: 1, TacticName: sm80_xmma_deconv_implicit_gemm_indexed_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize256x128x32_stage3_warpsize4x2x1_g1_tensor16x8x16_strided, TacticValue: 0xdec24e75875e331b +Name: Conv_60 + Relu_61, LayerType: CaskConvolution, Inputs: [ { Name: input.164, Location: Device, Dimensions: [1,512,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: onnx::Conv_651, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 64, Groups: 1, Weights: {"Type": "Half", "Count": 294912}, Bias: {"Type": "Half", "Count": 64}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x64x32_stage5_warpsize2x2x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0xb4bec086187edcfc +Name: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, LayerType: CaskConvolution, Inputs: [ { Name: onnx::Conv_651, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, Location: Device, Dimensions: [1,512,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 512, Groups: 1, Weights: {"Type": "Half", "Count": 294912}, Bias: {"Type": "Half", "Count": 512}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1, TacticValue: 0xa927df92ac1ef1b8 +Name: Conv_64, LayerType: CaskConvolution, Inputs: [ { Name: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_64, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_64, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_64, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: reg_0, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_67, LayerType: CaskConvolution, Inputs: [ { Name: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_67, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 1, Groups: 1, Weights: {"Type": "Half", "Count": 576}, Bias: {"Type": "Half", "Count": 1}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_67, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_67, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: height_0, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_70, LayerType: CaskConvolution, Inputs: [ { Name: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_70, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 3, Groups: 1, Weights: {"Type": "Half", "Count": 1728}, Bias: {"Type": "Half", "Count": 3}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_70, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_70, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: dim_0, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_73, LayerType: CaskConvolution, Inputs: [ { Name: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_73, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_73, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_73, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: rot_0, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_76, LayerType: CaskConvolution, Inputs: [ { Name: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_76, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_76, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_76, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: vel_0, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_79, LayerType: CaskConvolution, Inputs: [ { Name: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_79, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 1, Groups: 1, Weights: {"Type": "Half", "Count": 576}, Bias: {"Type": "Half", "Count": 1}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_79, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_79, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: hm_0, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_82, LayerType: CaskConvolution, Inputs: [ { Name: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_82, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_82, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_82, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: reg_1, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_85, LayerType: CaskConvolution, Inputs: [ { Name: Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_85, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 1, Groups: 1, Weights: {"Type": "Half", "Count": 576}, Bias: {"Type": "Half", "Count": 1}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_85, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_85, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: height_1, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, LayerType: CaskConvolution, Inputs: [ { Name: onnx::Conv_651, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, Location: Device, Dimensions: [1,512,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 512, Groups: 1, Weights: {"Type": "Half", "Count": 294912}, Bias: {"Type": "Half", "Count": 512}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1, TacticValue: 0xa927df92ac1ef1b8 +Name: Conv_88, LayerType: CaskConvolution, Inputs: [ { Name: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_88, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 3, Groups: 1, Weights: {"Type": "Half", "Count": 1728}, Bias: {"Type": "Half", "Count": 3}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_88, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_88, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: dim_1, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_91, LayerType: CaskConvolution, Inputs: [ { Name: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_91, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_91, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_91, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: rot_1, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_94, LayerType: CaskConvolution, Inputs: [ { Name: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_94, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_94, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_94, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: vel_1, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_97, LayerType: CaskConvolution, Inputs: [ { Name: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_97, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_97, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_97, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: hm_1, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_100, LayerType: CaskConvolution, Inputs: [ { Name: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_100, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_100, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_100, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: reg_2, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_103, LayerType: CaskConvolution, Inputs: [ { Name: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_103, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 1, Groups: 1, Weights: {"Type": "Half", "Count": 576}, Bias: {"Type": "Half", "Count": 1}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_103, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_103, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: height_2, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_106, LayerType: CaskConvolution, Inputs: [ { Name: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_106, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 3, Groups: 1, Weights: {"Type": "Half", "Count": 1728}, Bias: {"Type": "Half", "Count": 3}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_106, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_106, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: dim_2, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_109, LayerType: CaskConvolution, Inputs: [ { Name: Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_109, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_109, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_109, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: rot_2, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, LayerType: CaskConvolution, Inputs: [ { Name: onnx::Conv_651, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, Location: Device, Dimensions: [1,512,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 512, Groups: 1, Weights: {"Type": "Half", "Count": 294912}, Bias: {"Type": "Half", "Count": 512}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1, TacticValue: 0xa927df92ac1ef1b8 +Name: Conv_112, LayerType: CaskConvolution, Inputs: [ { Name: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_112, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_112, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_112, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: vel_2, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_115, LayerType: CaskConvolution, Inputs: [ { Name: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_115, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_115, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_115, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: hm_2, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_118, LayerType: CaskConvolution, Inputs: [ { Name: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_118, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_118, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_118, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: reg_3, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_121, LayerType: CaskConvolution, Inputs: [ { Name: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_121, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 1, Groups: 1, Weights: {"Type": "Half", "Count": 576}, Bias: {"Type": "Half", "Count": 1}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_121, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_121, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: height_3, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_124, LayerType: CaskConvolution, Inputs: [ { Name: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_124, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 3, Groups: 1, Weights: {"Type": "Half", "Count": 1728}, Bias: {"Type": "Half", "Count": 3}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_124, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_124, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: dim_3, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_127, LayerType: CaskConvolution, Inputs: [ { Name: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_127, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_127, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_127, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: rot_3, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_130, LayerType: CaskConvolution, Inputs: [ { Name: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_130, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_130, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_130, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: vel_3, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_133, LayerType: CaskConvolution, Inputs: [ { Name: Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_133, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 1, Groups: 1, Weights: {"Type": "Half", "Count": 576}, Bias: {"Type": "Half", "Count": 1}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_133, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_133, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: hm_3, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, LayerType: CaskConvolution, Inputs: [ { Name: onnx::Conv_651, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, Location: Device, Dimensions: [1,512,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 512, Groups: 1, Weights: {"Type": "Half", "Count": 294912}, Bias: {"Type": "Half", "Count": 512}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1, TacticValue: 0xa927df92ac1ef1b8 +Name: Conv_136, LayerType: CaskConvolution, Inputs: [ { Name: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_136, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_136, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_136, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: reg_4, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_139, LayerType: CaskConvolution, Inputs: [ { Name: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_139, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 1, Groups: 1, Weights: {"Type": "Half", "Count": 576}, Bias: {"Type": "Half", "Count": 1}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_139, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_139, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: height_4, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_142, LayerType: CaskConvolution, Inputs: [ { Name: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_142, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 3, Groups: 1, Weights: {"Type": "Half", "Count": 1728}, Bias: {"Type": "Half", "Count": 3}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_142, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_142, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: dim_4, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_145, LayerType: CaskConvolution, Inputs: [ { Name: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_145, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_145, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_145, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: rot_4, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_148, LayerType: CaskConvolution, Inputs: [ { Name: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_148, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_148, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_148, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: vel_4, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_151, LayerType: CaskConvolution, Inputs: [ { Name: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_151, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_151, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_151, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: hm_4, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_154, LayerType: CaskConvolution, Inputs: [ { Name: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_154, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_154, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_154, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: reg_5, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_157, LayerType: CaskConvolution, Inputs: [ { Name: Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_157, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 1, Groups: 1, Weights: {"Type": "Half", "Count": 576}, Bias: {"Type": "Half", "Count": 1}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_157, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_157, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: height_5, Location: Device, Dimensions: [1,1,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168, LayerType: CaskConvolution, Inputs: [ { Name: onnx::Conv_651, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168, Location: Device, Dimensions: [1,256,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 256, Groups: 1, Weights: {"Type": "Half", "Count": 147456}, Bias: {"Type": "Half", "Count": 256}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: RELU, HasBias: 1, HasReLU: 1, TacticName: ampere_h1688cudnn_128x128_ldg8_relu_exp_large_nhwc_tn_v1, TacticValue: 0xa927df92ac1ef1b8 +Name: Conv_160, LayerType: CaskConvolution, Inputs: [ { Name: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_160, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 3, Groups: 1, Weights: {"Type": "Half", "Count": 1728}, Bias: {"Type": "Half", "Count": 3}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_160, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_160, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: dim_5, Location: Device, Dimensions: [1,3,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_163, LayerType: CaskConvolution, Inputs: [ { Name: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_163, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_163, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_163, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: rot_5, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_166, LayerType: CaskConvolution, Inputs: [ { Name: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_166, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_166, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_166, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: vel_5, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 +Name: Conv_169, LayerType: CaskConvolution, Inputs: [ { Name: Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168, Location: Device, Dimensions: [1,64,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: Reformatted Output Tensor 0 to Conv_169, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], ParameterType: Convolution, Kernel: [3,3], PaddingMode: kEXPLICIT_ROUND_DOWN, PrePadding: [1,1], PostPadding: [1,1], Stride: [1,1], Dilation: [1,1], OutMaps: 2, Groups: 1, Weights: {"Type": "Half", "Count": 1152}, Bias: {"Type": "Half", "Count": 2}, HasSparseWeights: 0, HasDynamicFilter: 0, HasDynamicBias: 0, HasResidual: 0, ConvXAsActInputIdx: -1, BiasAsActInputIdx: -1, ResAsActInputIdx: -1, Activation: NONE, HasBias: 1, HasReLU: 0, TacticName: sm80_xmma_fprop_implicit_gemm_f16f16_f16f16_f16_nhwckrsc_nhwc_tilesize128x32x32_stage4_warpsize4x1x1_g1_tensor16x8x16_t1r3s3, TacticValue: 0x3e7eb35b91b9fa63 +Name: Reformatting CopyNode for Output Tensor 0 to Conv_169, LayerType: Reformat, Inputs: [ { Name: Reformatted Output Tensor 0 to Conv_169, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Channel major FP16 format where channel % 8 == 0 }], Outputs: [ { Name: hm_5, Location: Device, Dimensions: [1,2,180,180], Format/Datatype: Row major linear FP16 format }], ParameterType: Reformat, Origin: REFORMAT, TacticValue: 0x0000000000000000 + +Bindings: +input +reg_0 +height_0 +dim_0 +rot_0 +vel_0 +hm_0 +reg_1 +height_1 +dim_1 +rot_1 +vel_1 +hm_1 +reg_2 +height_2 +dim_2 +rot_2 +vel_2 +hm_2 +reg_3 +height_3 +dim_3 +rot_3 +vel_3 +hm_3 +reg_4 +height_4 +dim_4 +rot_4 +vel_4 +hm_4 +reg_5 +height_5 +dim_5 +rot_5 +vel_5 +hm_5 +[03/18/2024-15:13:29] [I] Starting inference +[03/18/2024-15:13:32] [I] Warmup completed 11 queries over 200 ms +[03/18/2024-15:13:32] [I] Timing trace has 249 queries over 3.03126 s +[03/18/2024-15:13:32] [I] +[03/18/2024-15:13:32] [I] === Trace details === +[03/18/2024-15:13:32] [I] Trace averages of 10 runs: +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.6643 ms - Host latency: 13.423 ms (enqueue 0.807605 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.9368 ms - Host latency: 13.694 ms (enqueue 0.67587 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.6609 ms - Host latency: 13.4147 ms (enqueue 0.729416 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.8811 ms - Host latency: 13.6372 ms (enqueue 0.699658 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 12.2292 ms - Host latency: 13.9877 ms (enqueue 0.68432 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 14.5462 ms - Host latency: 16.3037 ms (enqueue 0.720087 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 12.1229 ms - Host latency: 13.8782 ms (enqueue 0.702087 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.9336 ms - Host latency: 13.6888 ms (enqueue 0.704211 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.9069 ms - Host latency: 13.7303 ms (enqueue 0.951208 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.9083 ms - Host latency: 13.6807 ms (enqueue 0.681897 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.8758 ms - Host latency: 13.6969 ms (enqueue 0.727478 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.9309 ms - Host latency: 13.6867 ms (enqueue 0.719092 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.9569 ms - Host latency: 13.7123 ms (enqueue 0.766309 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 12.6852 ms - Host latency: 14.4426 ms (enqueue 0.729565 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 12.2629 ms - Host latency: 14.0157 ms (enqueue 0.651001 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 12.0217 ms - Host latency: 13.7795 ms (enqueue 0.710071 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.9061 ms - Host latency: 13.6601 ms (enqueue 0.686865 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.9665 ms - Host latency: 13.7245 ms (enqueue 0.796436 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 12.072 ms - Host latency: 13.829 ms (enqueue 0.820142 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.9478 ms - Host latency: 13.6973 ms (enqueue 0.706299 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 11.9082 ms - Host latency: 13.6651 ms (enqueue 0.692993 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 12.2937 ms - Host latency: 14.0456 ms (enqueue 0.681274 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 12.3692 ms - Host latency: 14.1473 ms (enqueue 0.778052 ms) +[03/18/2024-15:13:32] [I] Average on 10 runs - GPU latency: 12.1066 ms - Host latency: 13.8626 ms (enqueue 0.69707 ms) +[03/18/2024-15:13:32] [I] +[03/18/2024-15:13:32] [I] === Performance summary === +[03/18/2024-15:13:32] [I] Throughput: 82.144 qps +[03/18/2024-15:13:32] [I] Latency: min = 12.016 ms, max = 18.9825 ms, mean = 13.8881 ms, median = 13.8586 ms, percentile(90%) = 14.9219 ms, percentile(95%) = 15.3739 ms, percentile(99%) = 18.1702 ms +[03/18/2024-15:13:32] [I] Enqueue Time: min = 0.196533 ms, max = 1.59167 ms, mean = 0.726447 ms, median = 0.715576 ms, percentile(90%) = 1.0022 ms, percentile(95%) = 1.06018 ms, percentile(99%) = 1.2395 ms +[03/18/2024-15:13:32] [I] H2D Latency: min = 1.29395 ms, max = 1.47339 ms, mean = 1.31596 ms, median = 1.30774 ms, percentile(90%) = 1.33057 ms, percentile(95%) = 1.38062 ms, percentile(99%) = 1.43176 ms +[03/18/2024-15:13:32] [I] GPU Compute Time: min = 10.2625 ms, max = 17.2349 ms, mean = 12.1256 ms, median = 12.0833 ms, percentile(90%) = 13.1164 ms, percentile(95%) = 13.6274 ms, percentile(99%) = 16.3922 ms +[03/18/2024-15:13:32] [I] D2H Latency: min = 0.41626 ms, max = 0.470459 ms, mean = 0.446485 ms, median = 0.446533 ms, percentile(90%) = 0.451538 ms, percentile(95%) = 0.452881 ms, percentile(99%) = 0.461792 ms +[03/18/2024-15:13:32] [I] Total Host Walltime: 3.03126 s +[03/18/2024-15:13:32] [I] Total GPU Compute Time: 3.01928 s +[03/18/2024-15:13:32] [W] * GPU compute time is unstable, with coefficient of variance = 8.10125%. +[03/18/2024-15:13:32] [W] If not already in use, locking GPU clock frequency or adding --useSpinWait may improve the stability. +[03/18/2024-15:13:32] [I] Explanations of the performance metrics are printed in the verbose logs. +[03/18/2024-15:13:32] [V] +[03/18/2024-15:13:32] [V] === Explanations of the performance metrics === +[03/18/2024-15:13:32] [V] Total Host Walltime: the host walltime from when the first query (after warmups) is enqueued to when the last query is completed. +[03/18/2024-15:13:32] [V] GPU Compute Time: the GPU latency to execute the kernels for a query. +[03/18/2024-15:13:32] [V] Total GPU Compute Time: the summation of the GPU Compute Time of all the queries. If this is significantly shorter than Total Host Walltime, the GPU may be under-utilized because of host-side overheads or data transfers. +[03/18/2024-15:13:32] [V] Throughput: the observed throughput computed by dividing the number of queries by the Total Host Walltime. If this is significantly lower than the reciprocal of GPU Compute Time, the GPU may be under-utilized because of host-side overheads or data transfers. +[03/18/2024-15:13:32] [V] Enqueue Time: the host latency to enqueue a query. If this is longer than GPU Compute Time, the GPU may be under-utilized. +[03/18/2024-15:13:32] [V] H2D Latency: the latency for host-to-device data transfers for input tensors of a single query. +[03/18/2024-15:13:32] [V] D2H Latency: the latency for device-to-host data transfers for output tensors of a single query. +[03/18/2024-15:13:32] [V] Latency: the summation of H2D Latency, GPU Compute Time, and D2H Latency. This is the latency to infer a single query. +[03/18/2024-15:13:32] [I] +[03/18/2024-15:13:35] [I] +[03/18/2024-15:13:35] [I] === Profile (253 iterations ) === +[03/18/2024-15:13:35] [I] Layer Time (ms) Avg. Time (ms) Median Time (ms) Time % +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Input Tensor 0 to Conv_15 + Relu_16 33.28 0.1315 0.1302 1.2 +[03/18/2024-15:13:35] [I] Conv_15 + Relu_16 150.07 0.5932 0.5929 5.2 +[03/18/2024-15:13:35] [I] Conv_17 + Relu_18 80.75 0.3192 0.3185 2.8 +[03/18/2024-15:13:35] [I] Conv_19 + Relu_20 80.48 0.3181 0.3174 2.8 +[03/18/2024-15:13:35] [I] Conv_21 + Relu_22 80.44 0.3179 0.3174 2.8 +[03/18/2024-15:13:35] [I] Conv_23 + Relu_24 80.63 0.3187 0.3185 2.8 +[03/18/2024-15:13:35] [I] Conv_25 + Relu_26 111.82 0.4420 0.3205 3.9 +[03/18/2024-15:13:35] [I] Conv_27 + Relu_28 29.67 0.1173 0.1167 1.0 +[03/18/2024-15:13:35] [I] Conv_44 + Relu_45 44.48 0.1758 0.1751 1.5 +[03/18/2024-15:13:35] [I] Conv_46 + Relu_47 79.74 0.3152 0.3154 2.8 +[03/18/2024-15:13:35] [I] Conv_48 + Relu_49 79.90 0.3158 0.3154 2.8 +[03/18/2024-15:13:35] [I] Conv_50 + Relu_51 79.74 0.3152 0.3154 2.8 +[03/18/2024-15:13:35] [I] Conv_52 + Relu_53 79.65 0.3148 0.3154 2.8 +[03/18/2024-15:13:35] [I] Conv_54 + Relu_55 103.28 0.4082 0.3154 3.6 +[03/18/2024-15:13:35] [I] ConvTranspose_56 + BatchNormalization_57 + Relu_58 74.01 0.2925 0.2088 2.6 +[03/18/2024-15:13:35] [I] Conv_60 + Relu_61 157.47 0.6224 0.6216 5.5 +[03/18/2024-15:13:35] [I] Conv_62 + Relu_63 || Conv_65 + Relu_66 || Conv_68 + Relu_69 || Conv_71 + Relu_72 || Conv_74 + Relu_75 || Conv_77 + Relu_78 || Conv_80 + Relu_81 || Conv_83 + Relu_84 158.82 0.6278 0.6269 5.5 +[03/18/2024-15:13:35] [I] Conv_64 18.87 0.0746 0.0748 0.7 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_64 1.52 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_67 18.58 0.0734 0.0735 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_67 1.49 0.0059 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_70 18.27 0.0722 0.0719 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_70 1.52 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_73 18.41 0.0727 0.0727 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_73 1.53 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_76 18.60 0.0735 0.0696 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_76 1.51 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_79 19.20 0.0759 0.0705 0.7 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_79 2.92 0.0115 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_82 22.92 0.0906 0.0727 0.8 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_82 2.21 0.0088 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_85 23.37 0.0924 0.0727 0.8 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_85 4.12 0.0163 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_86 + Relu_87 || Conv_89 + Relu_90 || Conv_92 + Relu_93 || Conv_95 + Relu_96 || Conv_98 + Relu_99 || Conv_101 + Relu_102 || Conv_104 + Relu_105 || Conv_107 + Relu_108 175.40 0.6933 0.6287 6.1 +[03/18/2024-15:13:35] [I] Conv_88 18.78 0.0742 0.0739 0.7 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_88 1.57 0.0062 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_91 18.07 0.0714 0.0717 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_91 1.50 0.0059 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_94 17.86 0.0706 0.0707 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_94 1.53 0.0061 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_97 17.96 0.0710 0.0707 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_97 1.52 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_100 18.27 0.0722 0.0717 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_100 1.52 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_103 18.42 0.0728 0.0727 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_103 1.51 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_106 18.42 0.0728 0.0727 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_106 1.52 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_109 18.44 0.0729 0.0727 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_109 1.51 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_110 + Relu_111 || Conv_113 + Relu_114 || Conv_116 + Relu_117 || Conv_119 + Relu_120 || Conv_122 + Relu_123 || Conv_125 + Relu_126 || Conv_128 + Relu_129 || Conv_131 + Relu_132 159.98 0.6323 0.6245 5.6 +[03/18/2024-15:13:35] [I] Conv_112 21.99 0.0869 0.0735 0.8 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_112 1.51 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_115 23.51 0.0929 0.0707 0.8 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_115 1.51 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_118 25.68 0.1015 0.0696 0.9 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_118 2.27 0.0090 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_121 24.93 0.0985 0.0717 0.9 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_121 1.49 0.0059 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_124 26.78 0.1058 0.0717 0.9 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_124 1.85 0.0073 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_127 21.47 0.0849 0.0727 0.7 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_127 1.51 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_130 18.79 0.0743 0.0717 0.7 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_130 1.50 0.0059 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_133 17.97 0.0710 0.0707 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_133 1.50 0.0059 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_134 + Relu_135 || Conv_137 + Relu_138 || Conv_140 + Relu_141 || Conv_143 + Relu_144 || Conv_146 + Relu_147 || Conv_149 + Relu_150 || Conv_152 + Relu_153 || Conv_155 + Relu_156 157.96 0.6244 0.6236 5.5 +[03/18/2024-15:13:35] [I] Conv_136 18.65 0.0737 0.0737 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_136 1.51 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_139 18.02 0.0712 0.0707 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_139 1.54 0.0061 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_142 18.18 0.0719 0.0717 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_142 1.50 0.0059 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_145 18.44 0.0729 0.0727 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_145 1.51 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_148 18.37 0.0726 0.0727 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_148 1.53 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_151 17.87 0.0706 0.0704 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_151 1.52 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_154 18.17 0.0718 0.0717 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_154 1.49 0.0059 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_157 17.74 0.0701 0.0699 0.6 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_157 1.51 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_158 + Relu_159 || Conv_161 + Relu_162 || Conv_164 + Relu_165 || Conv_167 + Relu_168 85.33 0.3373 0.3186 3.0 +[03/18/2024-15:13:35] [I] Conv_160 26.34 0.1041 0.0748 0.9 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_160 3.11 0.0123 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_163 27.60 0.1091 0.0737 1.0 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_163 1.52 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_166 24.31 0.0961 0.0737 0.8 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_166 1.51 0.0060 0.0061 0.1 +[03/18/2024-15:13:35] [I] Conv_169 21.72 0.0859 0.0737 0.8 +[03/18/2024-15:13:35] [I] Reformatting CopyNode for Output Tensor 0 to Conv_169 2.00 0.0079 0.0061 0.1 +[03/18/2024-15:13:35] [I] Total 2876.29 11.3687 11.3357 100.0 +[03/18/2024-15:13:35] [I] +&&&& PASSED TensorRT.trtexec [TensorRT v8503] # trtexec --onnx=model/rpn_centerhead_sim.onnx --saveEngine=model/rpn_centerhead_sim.plan.8513 --workspace=4096 --fp16 --outputIOFormats=fp16:chw --inputIOFormats=fp16:chw --verbose --dumpLayerInfo --dumpProfile --separateProfileRun --profilingVerbosity=detailed diff --git a/trlo/model/center_pointpillars/rpn_centerhead_sim.onnx b/trlo/model/center_pointpillars/rpn_centerhead_sim.onnx new file mode 100644 index 0000000..dba5d67 Binary files /dev/null and b/trlo/model/center_pointpillars/rpn_centerhead_sim.onnx differ diff --git a/trlo/model/center_pointpillars/rpn_centerhead_sim.plan b/trlo/model/center_pointpillars/rpn_centerhead_sim.plan new file mode 120000 index 0000000..c191563 --- /dev/null +++ b/trlo/model/center_pointpillars/rpn_centerhead_sim.plan @@ -0,0 +1 @@ +/home/jyp/3D_LiDAR_SLAM/Lidar_AI_Solution/CUDA-CenterPoint/model/rpn_centerhead_sim.plan.8513 \ No newline at end of file diff --git a/trlo/model/center_pointpillars/rpn_centerhead_sim.plan.8513 b/trlo/model/center_pointpillars/rpn_centerhead_sim.plan.8513 new file mode 100644 index 0000000..e337011 Binary files /dev/null and b/trlo/model/center_pointpillars/rpn_centerhead_sim.plan.8513 differ diff --git a/trlo/package.xml b/trlo/package.xml new file mode 100644 index 0000000..699fe1b --- /dev/null +++ b/trlo/package.xml @@ -0,0 +1,29 @@ + + + + + trlo + 1.0.0 + TRLO: Efficient LiDAR Odometry with 3D Objects Traking and Removal + + Yanpeng Jia + + Yanpeng Jia + + UCAS + + catkin + + message_generation + message_runtime + + roscpp + std_msgs + sensor_msgs + geometry_msgs + pcl_ros + + + + + \ No newline at end of file diff --git "a/trlo/src/2024-03-23 12-42-08 \347\232\204\345\261\217\345\271\225\346\210\252\345\233\276.png" "b/trlo/src/2024-03-23 12-42-08 \347\232\204\345\261\217\345\271\225\346\210\252\345\233\276.png" new file mode 100644 index 0000000..06cc6b4 Binary files /dev/null and "b/trlo/src/2024-03-23 12-42-08 \347\232\204\345\261\217\345\271\225\346\210\252\345\233\276.png" differ diff --git a/trlo/src/3d_mot/3d_mot_node.cpp b/trlo/src/3d_mot/3d_mot_node.cpp new file mode 100644 index 0000000..3d0c1b4 --- /dev/null +++ b/trlo/src/3d_mot/3d_mot_node.cpp @@ -0,0 +1,406 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +#include + +#include +#include +#include + +// PCL specific includes +#include +#include +#include +#include +#include +#include +#include "pcl_ros/impl/transforms.hpp" + +#include +#include +#include +#include "tf/transform_datatypes.h" +#include +#include + +#include +#include + +#include + +#include "3d_mot/imm_ukf_jpda.h" + +ros::Subscriber sub; +ros::Subscriber sub_odom; +ros::Publisher pub_track_box; +ros::Publisher vis_pub; +ros::Publisher vis_pub2; + +tf::TransformListener* tran; + +std::deque odom_queue; + +pcl::PointCloud::Ptr color_point(new pcl::PointCloud()); + +int counta = 0; +ros::Time last_time; + +// 回调函数-- 话题 track_box +void track_box (const jsk_recognition_msgs::BoundingBoxArrayPtr &input){ + + + counta ++; + cout << "Frame: "<header.stamp.toSec(); + ros::Time input_time = input->header.stamp; + + int box_num = input->boxes.size(); + + vector> bBoxes; + PointCloud oneBbox; +// bBoxes.header = input.header; + for(int i = 0; i < box_num; i++) + { + PointXYZ o; + o.x = input->boxes[i].pose.position.x - input->boxes[i].dimensions.y / 2; + o.y = input->boxes[i].pose.position.y - input->boxes[i].dimensions.x / 2; + o.z = input->boxes[i].pose.position.z - input->boxes[i].dimensions.z / 2; + oneBbox.push_back(o); + o.x = input->boxes[i].pose.position.x + input->boxes[i].dimensions.y / 2; + o.y = input->boxes[i].pose.position.y - input->boxes[i].dimensions.x / 2; + o.z = input->boxes[i].pose.position.z - input->boxes[i].dimensions.z / 2; + oneBbox.push_back(o); + o.x = input->boxes[i].pose.position.x - input->boxes[i].dimensions.y / 2; + o.y = input->boxes[i].pose.position.y + input->boxes[i].dimensions.x / 2; + o.z = input->boxes[i].pose.position.z - input->boxes[i].dimensions.z / 2; + oneBbox.push_back(o); + o.x = input->boxes[i].pose.position.x + input->boxes[i].dimensions.y / 2; + o.y = input->boxes[i].pose.position.y + input->boxes[i].dimensions.x / 2; + o.z = input->boxes[i].pose.position.z - input->boxes[i].dimensions.z / 2; + oneBbox.push_back(o); + o.x = input->boxes[i].pose.position.x - input->boxes[i].dimensions.y / 2; + o.y = input->boxes[i].pose.position.y - input->boxes[i].dimensions.x / 2; + o.z = input->boxes[i].pose.position.z + input->boxes[i].dimensions.z / 2; + oneBbox.push_back(o); + o.x = input->boxes[i].pose.position.x + input->boxes[i].dimensions.y / 2; + o.y = input->boxes[i].pose.position.y - input->boxes[i].dimensions.x / 2; + o.z = input->boxes[i].pose.position.z + input->boxes[i].dimensions.z / 2; + oneBbox.push_back(o); + o.x = input->boxes[i].pose.position.x - input->boxes[i].dimensions.y / 2; + o.y = input->boxes[i].pose.position.y + input->boxes[i].dimensions.x / 2; + o.z = input->boxes[i].pose.position.z + input->boxes[i].dimensions.z / 2; + oneBbox.push_back(o); + o.x = input->boxes[i].pose.position.x + input->boxes[i].dimensions.y / 2; + o.y = input->boxes[i].pose.position.y + input->boxes[i].dimensions.x / 2; + o.z = input->boxes[i].pose.position.z + input->boxes[i].dimensions.z / 2; + oneBbox.push_back(o); + bBoxes.push_back(oneBbox); + oneBbox.clear(); + } + + // std::cout << "!!!!!input->boxes[i].pose.position.x: " << input->boxes[0].pose.position.x << std::endl; + + tf::StampedTransform transform; + + // static bool first = 1; + // if (first) + // last_time = input_time; + // first = 0; + // return; + + // while (odom_queue.front().header.stamp != last_time) { + // odom_queue.pop_front(); + // } + if (odom_queue.empty()) + return; + // std::cout << odom_queue.front().pose.pose.position.x << "!!!!!!!!!!!!!!!!!!!!!!!!!" << std::endl; + + // transform.setOrigin( tf::Vector3(odom_queue.front().pose.pose.position.x, odom_queue.front().pose.pose.position.y, 0.0) ); + // tf::Quaternion q(odom_queue.front().pose.pose.orientation.x, odom_queue.front().pose.pose.orientation.y, odom_queue.front().pose.pose.orientation.z, odom_queue.front().pose.pose.orientation.w); + + // transform.setRotation( q ); + // tran->setTransform(transform); + + + PointCloud newBox; + for(int i = 0; i < box_num; i++ ){ + bBoxes[i].header.frame_id = "robot/odom"; + + // tran->waitForTransform("robot/odom", "robot/base_link", last_time, ros::Duration(10.0)); + // pcl_ros::transformPointCloud("robot/odom", bBoxes[i], newBox, *tran); + Eigen::Matrix4f last_T; + Eigen::Quaternionf last_q(odom_queue.front().pose.pose.orientation.w, odom_queue.front().pose.pose.orientation.x, odom_queue.front().pose.pose.orientation.y, odom_queue.front().pose.pose.orientation.z); + last_T.block<3,3>(0,0) = last_q.toRotationMatrix(); + last_T.block<3,1>(0,3) = Eigen::Vector3f(odom_queue.front().pose.pose.position.x, odom_queue.front().pose.pose.position.y, 0.0); + pcl::transformPointCloud(bBoxes[i], newBox, last_T); + bBoxes[i] = newBox; + bBoxes[i].header.frame_id = "robot/odom"; + // std::cout << "!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!" << std::endl; + } + + for (int i = 0; i < bBoxes.size(); i++) { + *color_point += bBoxes[i]; + } + + sensor_msgs::PointCloud2 cloud_msg; + pcl::toROSMsg(*color_point, cloud_msg); + cloud_msg.header = input->header; + cloud_msg.header.frame_id = "robot/odom"; + pub_track_box.publish(cloud_msg); + + //end converting---------------------------------------- + PointCloud targetPoints; + vector> targetVandYaw; + vector trackManage; // trackManage??? 大量具有相关不确定性的跟踪对象需要有效地实施跟踪管理。跟踪管理的主要目的是动态限制虚假跟踪列表的数量(从而防止错误的数据关联),并在丢失检测的情况下保持对象跟踪 + vector isStaticVec; + vector isVisVec; + vector> visBBs; + // std::cout << "!!!!!input->boxes[i].pose.position.x: " << bBoxes[0][0] << std::endl; + immUkfJpdaf(bBoxes, timestamp, targetPoints, targetVandYaw, trackManage, isStaticVec, isVisVec, visBBs); + +// // cout << "size is "<(0,0) = last_q.toRotationMatrix().inverse(); + Eigen::Vector3f t(odom_queue.front().pose.pose.position.x, odom_queue.front().pose.pose.position.y, 0.0); + t = -last_T.block<3,3>(0,0) * t; + last_T.block<3,1>(0,3) = t; + + // converting from global to ego tf for visualization + // processing targetPoints + PointCloud egoTFPoints; + targetPoints.header.frame_id = "robot/base_link"; + // pcl_ros::transformPointCloud("/velodyne", targetPoints, egoTFPoints, *tran); + pcl::transformPointCloud(targetPoints, egoTFPoints, last_T); + + //processing visBBs + PointCloud visEgoBB; + for(int i = 0; i < visBBs.size(); i++){ + visBBs[i].header.frame_id = "robot/base_link"; + // pcl_ros::transformPointCloud("/velodyne", visBBs[i], visEgoBB, *tran); + pcl::transformPointCloud(visBBs[i], visEgoBB, last_T); + + visBBs[i] = visEgoBB; + } + //end converting to ego tf------------------------- + + + + + + // tracking arrows visualizing start--------------------------------------------- + for(int i = 0; i < targetPoints.size(); i++){ + visualization_msgs::Marker arrowsG; + arrowsG.lifetime = ros::Duration(0.1); + if(trackManage[i] == 0 ) { + continue; + } + if(isVisVec[i] == false ) { + continue; + } + if(isStaticVec[i] == true){ + continue; + } +// arrowsG.header.frame_id = "/velo_link"; + arrowsG.header.frame_id = "robot/base_link"; + + arrowsG.header.stamp= input_time; + arrowsG.ns = "arrows"; + arrowsG.action = visualization_msgs::Marker::ADD; + arrowsG.type = visualization_msgs::Marker::ARROW; + // green 设置颜色 + arrowsG.color.g = 1.0f; // 绿色 + // arrowsG.color.r = 1.0f; // 红色 + arrowsG.color.a = 1.0; + arrowsG.id = i; + geometry_msgs::Point p; + // assert(targetPoints[i].size()==4); + p.x = egoTFPoints[i].x; + p.y = egoTFPoints[i].y; + p.z = -1.73/2; + double tv = targetVandYaw[i][0]; + double tyaw = targetVandYaw[i][1]; + + // Set the pose of the marker. This is a full 6DOF pose relative to the frame/time specified in the header + arrowsG.pose.position.x = p.x; + arrowsG.pose.position.y = p.y; + arrowsG.pose.position.z = p.z; + + // convert from 3 angles to quartenion + tf::Matrix3x3 obs_mat; + obs_mat.setEulerYPR(tyaw, 0, 0); // yaw, pitch, roll + tf::Quaternion q_tf; + obs_mat.getRotation(q_tf); + arrowsG.pose.orientation.x = q_tf.getX(); + arrowsG.pose.orientation.y = q_tf.getY(); + arrowsG.pose.orientation.z = q_tf.getZ(); + arrowsG.pose.orientation.w = q_tf.getW(); + + // Set the scale of the arrowsG -- 1x1x1 here means 1m on a side + arrowsG.scale.x = tv; + arrowsG.scale.y = 0.1; + arrowsG.scale.z = 0.1; + + vis_pub2.publish(arrowsG); // 发布箭头消息 + } + + + + + + + + + + + + + + + // tracking points visualizing start--------------------------------------------- + + visualization_msgs::Marker pointsY, pointsG, pointsR, pointsB; + pointsY.header.frame_id = pointsG.header.frame_id = pointsR.header.frame_id = pointsB.header.frame_id = "robot/base_link"; +// pointsY.header.frame_id = pointsG.header.frame_id = pointsR.header.frame_id = pointsB.header.frame_id = "velo_link"; + + pointsY.header.stamp= pointsG.header.stamp= pointsR.header.stamp =pointsB.header.stamp = input_time; + pointsY.ns= pointsG.ns = pointsR.ns =pointsB.ns= "points"; + pointsY.action = pointsG.action = pointsR.action = pointsB.action = visualization_msgs::Marker::ADD; + pointsY.pose.orientation.w = pointsG.pose.orientation.w = pointsR.pose.orientation.w =pointsB.pose.orientation.w= 1.0; + + pointsY.id = 1; + pointsG.id = 2; + pointsR.id = 3; + pointsB.id = 4; + pointsY.type = pointsG.type = pointsR.type = pointsB.type = visualization_msgs::Marker::POINTS; + + // POINTS markers use x and y scale for width/height respectively + pointsY.scale.x =pointsG.scale.x =pointsR.scale.x = pointsB.scale.x=0.5; + pointsY.scale.y =pointsG.scale.y =pointsR.scale.y = pointsB.scale.y = 0.5; + + // yellow(红绿蓝混合为黄) + pointsY.color.r = 1.0f; + pointsY.color.g = 1.0f; + pointsY.color.b = 0.0f; + pointsY.color.a = 1.0; + + // green + pointsG.color.g = 1.0f; + pointsG.color.a = 1.0; + + // red + pointsR.color.r = 1.0; + pointsR.color.a = 1.0; + + // blue + pointsB.color.b = 1.0; + pointsB.color.a = 1.0; + +// cout << "targetPoints.size() is --=------" << targetPoints.size() < 5){ + pointsR.points.push_back(p); // 大于5为红点 + } + } + vis_pub.publish(pointsY); // 发布 + // cout << "pointsG" << pointsG.points[0].x << " "<< pointsG.points[0].y << endl; + vis_pub.publish(pointsG); // 发布 + vis_pub.publish(pointsR); // 发布 + vis_pub.publish(pointsB); // 发布 + // tracking points visualizing end--------------------------------------------- + + + + odom_queue.pop_front(); + + + +} + +void odom_callback(const nav_msgs::OdometryPtr &odom) { + odom_queue.push_back(*odom); + // std::cout << "!!!!!!!!!!!!!!!!!!!!!!!!!!!! size: " << odom_queue.size() << std::endl; +} + + +int main(int argc, char **argv) { + ros::init (argc, argv, "3d_mot_node"); + + ros::NodeHandle nh("~"); + + // TF + tf::TransformListener lr(ros::Duration(100)); //(How long to store transform information) + tran=&lr; + + sub = nh.subscribe ("mot_box", 160, track_box); //订阅者 track_box -- 话题topic名 + sub_odom = nh.subscribe ("odom", 160, odom_callback); //订阅者 track_box -- 话题topic名 + // pub_track_box = nh.advertise("track_box", 10, true); + pub_track_box = nh.advertise("track_box", 10); + + vis_pub = nh.advertise( "tracking_center", 0 ); //发布者 visualization_marker -- 话题topic名 + vis_pub2 = nh.advertise( "object_vel_arrows", 0 ); //发布者 visualization_marker2 -- 话题topic名 + + + ros::spin(); +} + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/trlo/src/3d_mot/imm_ukf_jpda.cpp b/trlo/src/3d_mot/imm_ukf_jpda.cpp new file mode 100644 index 0000000..e9aa835 --- /dev/null +++ b/trlo/src/3d_mot/imm_ukf_jpda.cpp @@ -0,0 +1,878 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +#include +#include +#include +#include +#include + +#include "3d_mot/ukf.h" +#include "3d_mot/imm_ukf_jpda.h" + +using namespace std; +using namespace Eigen; +using namespace pcl; + + +bool init_= false; +double timestamp_ ; +double egoVelo_; +double egoYaw_; +double egoPreYaw_; +VectorXd preMeas_; + +const double gammaG_ = 9.22; // 99% +const double pG_ = 0.99; +const double pD_ = 0.9; +const double distanceThres_ = 99; + +const int lifeTimeThres_ = 3; + +//bbox update params +const double bbYawChangeThres_ = 0.2; +const double bbAreaChangeThres_ = 0.5; +const double bbVelThres_ = 0.05; +const double bbDeltaVel_ = 0.01; +const int nStepBack_ = 3; + +int countIt = 0; +vector targets_; +vector trackNumVec_; + +//testing recover origin tf +vector> egoPoints_; +vector> egoDeltaHis_; +vector egoDiffYaw_; + +void getOriginPoints(Eigen::Matrix3f pose){ + egoYaw_ = pose.eulerAngles(2, 1, 0)(0); +} + +void findMaxZandS(UKF target, VectorXd& maxDetZ, MatrixXd& maxDetS){ + double cv_det = target.lS_cv_.determinant(); + double ctrv_det = target.lS_ctrv_.determinant(); + double rm_det = target.lS_rm_.determinant(); + + if(cv_det > ctrv_det){ + if(cv_det > rm_det) { + maxDetZ = target.zPredCVl_; + maxDetS = target.lS_cv_; + } + else { + maxDetZ = target.zPredRMl_; + maxDetS = target.lS_rm_; + } + } + else{ + if(ctrv_det > rm_det) { + maxDetZ = target.zPredCTRVl_; + maxDetS = target.lS_ctrv_; + } + else { + maxDetZ = target.zPredRMl_; + maxDetS = target.lS_rm_; + } + } + + +} + +void measurementValidation(vector> trackPoints, UKF& target, bool secondInit, VectorXd maxDetZ, MatrixXd maxDetS, + vector& measVec, vector& bboxVec, vector& matchingVec){ + + int count = 0; + bool secondInitDone = false; + double smallestNIS = 999; + VectorXd smallestMeas = VectorXd(2); + int targetSize = trackPoints.size(); + for(int i = 0; i < targetSize; i++){ + double x = trackPoints[i][0]; + double y = trackPoints[i][1]; + VectorXd meas = VectorXd(2); + meas << x, y; + + VectorXd bbox = VectorXd(10); + bbox << x, y, + trackPoints[i][2], trackPoints[i][3], + trackPoints[i][4], trackPoints[i][5], + trackPoints[i][6], trackPoints[i][7], + trackPoints[i][8], trackPoints[i][9]; + + VectorXd diff = meas - maxDetZ; + double nis = diff.transpose()*maxDetS.inverse()*diff; + + if(nis < gammaG_){ // x^2 99% range + count ++; + if(matchingVec[i] == 0) target.lifetime_ ++; + + // pick one meas with smallest nis + if(secondInit){ + if(nis < smallestNIS){ + smallestNIS = nis; + smallestMeas = meas; + // measVec.push_back(meas); + matchingVec[i] = 1; + secondInitDone = true; + } + } + else{ + measVec.push_back(meas); + bboxVec.push_back(bbox); + matchingVec[i] = 1; + } + } + // cout << "meas"< measVec, vector& lambdaVec){ + // calculating association probability + // UKF one = targets[0]; + double numMeas = measVec.size(); + double b = 2*numMeas*(1-pD_*pG_)/(gammaG_*pD_); + double eCVSum = 0; + double eCTRVSum = 0; + double eRMSum = 0; + + vector eCvVec; + vector eCtrvVec; + vector eRmVec; + + vector diffCVVec; + vector diffCTRVVec; + vector diffRMVec; + + for(int i = 0; i < numMeas; i++){ + VectorXd diffCV = measVec[i] - target.zPredCVl_; + VectorXd diffCTRV = measVec[i] - target.zPredCTRVl_; + VectorXd diffRM = measVec[i] - target.zPredRMl_; + + diffCVVec.push_back(diffCV); + diffCTRVVec.push_back(diffCTRV); + diffRMVec.push_back(diffRM); + + double eCV = exp( -0.5*diffCV.transpose()* target.lS_cv_.inverse() *diffCV); + double eCTRV = exp(-0.5*diffCTRV.transpose()* target.lS_ctrv_.inverse()*diffCTRV); + double eRM = exp( -0.5*diffRM.transpose()* target.lS_rm_.inverse() *diffRM); + + eCvVec.push_back(eCV); + eCtrvVec.push_back(eCTRV); + eRmVec.push_back(eRM); + + eCVSum += eCV; + eCTRVSum += eCTRV; + eRMSum += eRM; + } + double betaCVZero = b/(b+eCVSum); + double betaCTRVZero = b/(b+eCTRVSum); + double betaRMZero = b/(b+eRMSum); + + vector betaCV; + vector betaCTRV; + vector betaRM; + + // cout << "beta cv" << endl; + for(int i = 0; i < numMeas; i++){ + double tempCV = eCvVec[i]/(b+eCVSum); + double tempCTRV = eCtrvVec[i]/(b+eCTRVSum); + double tempRM = eRmVec[i]/(b+eRMSum); + // cout << tempCV << endl; + betaCV.push_back(tempCV); + betaCTRV.push_back(tempCTRV); + betaRM.push_back(tempRM); + + } + VectorXd sigmaXcv; + VectorXd sigmaXctrv; + VectorXd sigmaXrm; + sigmaXcv.setZero(2); + sigmaXctrv.setZero(2); + sigmaXrm.setZero(2); + + for(int i = 0; i < numMeas; i++){ + sigmaXcv += betaCV[i]*diffCVVec[i]; + sigmaXctrv += betaCTRV[i]*diffCTRVVec[i]; + sigmaXrm += betaRM[i]*diffRMVec[i]; + } + + MatrixXd sigmaPcv; + MatrixXd sigmaPctrv; + MatrixXd sigmaPrm; + sigmaPcv.setZero(2,2); + sigmaPctrv.setZero(2,2); + sigmaPrm.setZero(2,2); + for(int i = 0; i < numMeas; i++){ + sigmaPcv += (betaCV[i] *diffCVVec[i] *diffCVVec[i].transpose() - sigmaXcv*sigmaXcv.transpose()); + sigmaPctrv += (betaCTRV[i]*diffCTRVVec[i]*diffCTRVVec[i].transpose() - sigmaXctrv*sigmaXctrv.transpose()); + sigmaPrm += (betaRM[i] *diffRMVec[i] *diffRMVec[i].transpose() - sigmaXrm*sigmaXrm.transpose()); + } + + // update x and P + target.x_cv_ = target.x_cv_ + target.K_cv_*sigmaXcv; + target.x_ctrv_ = target.x_ctrv_ + target.K_ctrv_*sigmaXctrv; + target.x_rm_ = target.x_rm_ + target.K_rm_*sigmaXrm; + while (target.x_cv_(3)> M_PI) target.x_cv_(3) -= 2.*M_PI; + while (target.x_cv_(3)<-M_PI) target.x_cv_(3) += 2.*M_PI; + while (target.x_ctrv_(3)> M_PI) target.x_ctrv_(3) -= 2.*M_PI; + while (target.x_ctrv_(3)<-M_PI) target.x_ctrv_(3) += 2.*M_PI; + while (target.x_rm_(3)> M_PI) target.x_rm_(3) -= 2.*M_PI; + while (target.x_rm_(3)<-M_PI) target.x_rm_(3) += 2.*M_PI; + + if(numMeas != 0){ + target.P_cv_ = betaCVZero*target.P_cv_ + + (1-betaCVZero)*(target.P_cv_ - target.K_cv_*target.lS_cv_*target.K_cv_.transpose()) + + target.K_cv_*sigmaPcv*target.K_cv_.transpose(); + target.P_ctrv_ = betaCTRVZero*target.P_ctrv_ + + (1-betaCTRVZero)*(target.P_ctrv_ - target.K_ctrv_*target.lS_ctrv_*target.K_ctrv_.transpose()) + + target.K_ctrv_*sigmaPctrv*target.K_ctrv_.transpose(); + target.P_rm_ = betaRMZero*target.P_rm_ + + (1-betaRMZero)*(target.P_rm_ - target.K_rm_*target.lS_rm_*target.K_rm_.transpose()) + + target.K_rm_*sigmaPrm*target.K_rm_.transpose(); + } + else{ + target.P_cv_ = target.P_cv_ - target.K_cv_ *target.lS_cv_ *target.K_cv_.transpose(); + target.P_ctrv_ = target.P_ctrv_ - target.K_ctrv_*target.lS_ctrv_*target.K_ctrv_.transpose(); + target.P_rm_ = target.P_rm_ - target.K_rm_ *target.lS_rm_ *target.K_rm_.transpose(); + } + // cout << "after update p cv: "< bboxVec, vector& Bbox, int& minDist){ + int minInd = 0; + double px = target.x_merge_(0); + double py = target.x_merge_(1); + for (int i = 0; i < bboxVec.size(); i++){ + double measX = bboxVec[i](0); + double measY = bboxVec[i](1); + double dist = sqrt((px-measX)*(px-measX)+(py-measY)*(py-measY)); + if(dist < minDist){ + minDist = dist; + minInd = i; + } + } + assert(bboxVec[minInd].rows() == 10); + for(int i = 0; i < 10; i++){ + Bbox.push_back(bboxVec[minInd](i)); + } +} + +void associateBB(int trackNum, vector bboxVec, UKF& target){ + //skip if no validated measurement + + // cout <<"bboxVec.size() is " << bboxVec.size() < lifeTimeThres_){ + vector nearestBbox; + int minDist = 999; + getNearestEuclidBBox(target, bboxVec, nearestBbox, minDist); + if(minDist < distanceThres_){ + PointCloud bbox; + PointXYZ o; + // transformTargetAnchorTF2Local(target.local2local_, target.local2localYawVec_, nearestBbox); + assert(nearestBbox.size() == 10); + for(int i = 0; i < 2; i++){ + double height; + if(i == 0) {height = -1.73;} + else {height = 0;} + o.x = nearestBbox[2]; + o.y = nearestBbox[3]; + o.z = height; + bbox.push_back(o); + o.x = nearestBbox[4]; + o.y = nearestBbox[5]; + o.z = height; + bbox.push_back(o); + o.x = nearestBbox[6]; + o.y = nearestBbox[7]; + o.z = height; + bbox.push_back(o); + o.x = nearestBbox[8]; + o.y = nearestBbox[9]; + o.z = height; + bbox.push_back(o); + } + target.isVisBB_ = true; + target.BBox_ = bbox; + } + } +} + +VectorXd getCpFromBbox(PointCloud bBox){ + PointXYZ p1 = bBox[0]; + PointXYZ p2 = bBox[1]; + PointXYZ p3 = bBox[2]; + PointXYZ p4 = bBox[3]; + + double cx = (p1.x + p2.x) / 2; + double cy = (p1.y + p4.y) / 2; + + VectorXd cp(2); + cp << cx, cy; + return cp; +} + +double getBboxArea(PointCloud bBox){ + PointXYZ p1 = bBox[0]; + PointXYZ p2 = bBox[1]; + PointXYZ p3 = bBox[2]; + PointXYZ p4 = bBox[3]; + + //S=tri(p1,p2,p3) + tri(p1, p3, p4) + //s(triangle) = 1/2*|(x1−x3)(y2−y3)−(x2−x3)(y1−y3)| + double tri1 = 0.5*abs((p1.x - p3.x)*(p2.y - p3.y) - (p2.x - p3.x)*(p1.y - p3.y)); + double tri2 = 0.5*abs((p1.x - p4.x)*(p3.y - p4.y) - (p3.x - p4.x)*(p1.y - p4.y)); + double S = tri1 + tri2; + return S; +} + +void updateVisBoxArea(UKF& target, VectorXd dtCP){ + int lastInd = target.bb_yaw_history_.size()-1; + // double diffYaw = target.bb_yaw_history_[lastInd] - target.bb_yaw_history_[lastInd-1]; + double area = getBboxArea(target.bestBBox_); + for(int i = 0; i < target.BBox_.size(); i++){ + target.BBox_[i].x = target.bestBBox_[i].x + dtCP(0); + target.BBox_[i].y = target.bestBBox_[i].y + dtCP(1); + } + + double postArea = getBboxArea(target.BBox_); + assert(abs(area - postArea)< 0.001); + +} + +void updateBoxYaw(UKF& target, VectorXd cp, double bestDiffYaw, bool isVis){ + + // cout << "before convert "<< target.BBox_[0].x << " "< bBox = target.BBox_; + PointXYZ p1 = bBox[0]; + PointXYZ p2 = bBox[1]; + PointXYZ p3 = bBox[2]; + double dist1 = sqrt((p1.x- p2.x)*(p1.x - p2.x) + (p1.y - p2.y)*(p1.y - p2.y)); + double dist2 = sqrt((p3.x- p2.x)*(p3.x - p2.x) + (p3.y - p2.y)*(p3.y - p2.y)); + + double yaw; + // dist1 is length + if(dist1>dist2){ + yaw = atan2(p1.y - p2.y, p1.x - p2.x); + } + else{ + yaw = atan2(p3.y - p2.y, p3.x - p2.x); + } + + double ukfYaw = target.x_merge_(3); + double diffYaw = abs(yaw - ukfYaw); + if(diffYaw < M_PI*0.5){ + return yaw; + } + else{ + yaw += M_PI; + while (yaw> M_PI) yaw -= 2.*M_PI; + while (yaw<-M_PI) yaw += 2.*M_PI; + return yaw; + } +} + +void updateBB(UKF& target){ + // skip to prevent memory leak by accessing empty target.bbox_ + if(!target.isVisBB_){ + return; + } + // skip the rest of process if the first bbox associaiton + if(target.bestBBox_.empty()){ + target.bestBBox_ = target.BBox_; + target.bestYaw_ = getBBoxYaw(target); + return; + } + + // calculate yaw + VectorXd cp = getCpFromBbox(target.BBox_); + VectorXd bestCP = getCpFromBbox(target.bestBBox_); + VectorXd dtCP = cp - bestCP; + double yaw = getBBoxYaw(target); + + // bbox area + double area = getBboxArea(target.BBox_); + double bestArea = getBboxArea(target.bestBBox_); + + // start updating parameters + double deltaArea = area - bestArea; + + // when the best area is bigger, keep best area + if( deltaArea < 0 ){ + updateVisBoxArea(target, dtCP); + } + else if(deltaArea > 0){ + target.bestBBox_ = target.BBox_; + // target.bestYaw_ = yaw; + } + // cout <<"after transform " < bbYawChangeThres_){ + // updateVisBoxYaw(target, cp, bestDiffYaw); + } + //when the diff is acceptable, update best yaw + else if(abs(DiffYaw) < bbYawChangeThres_){ + bool isVis = true; + updateBoxYaw(target, cp, DiffYaw, isVis); + isVis = false; + updateBoxYaw(target, cp, DiffYaw, isVis); + + double afterYaw = getBBoxYaw(target); + // cout << "box yaw after "<< afterYaw< targets){ + // cout << "mergeOverSegmentation"< 0 && cross2>0&&cross3>0)||(cross4>0 && cross5 > 0 && cross6>0)){ + // cout << "merrrrrrrrrrrrrrrrrrrrrrrrrrrrrrrrrrrrrrrge"<> bBoxes, double timestamp, + PointCloud& targetPoints, vector>& targetVandYaw, + vector& trackManage, vector& isStaticVec, + vector& isVisVec, vector>& visBBs){ + + countIt ++; + + // convert from bboxes to cx,cy + vector> trackPoints; + for(int i = 0; i < bBoxes.size(); i ++){ + PointXYZ p1 = bBoxes[i][0]; + PointXYZ p2 = bBoxes[i][1]; + PointXYZ p3 = bBoxes[i][2]; + PointXYZ p4 = bBoxes[i][3]; + + VectorXd cp = getCpFromBbox(bBoxes[i]); + + // cout << "trackpoitns "<< cp(0) <<" "< point; + point.push_back(cp(0)); + point.push_back(cp(1)); + point.push_back(p1.x); + point.push_back(p1.y); + point.push_back(p2.x); + point.push_back(p2.y); + point.push_back(p3.x); + point.push_back(p3.y); + point.push_back(p4.x); + point.push_back(p4.y); + + trackPoints.push_back(point); + } + + // cout << trackPoints[0][0] << endl; + + if(!init_) { + // cout << trackPoints.size()<< endl; + int targetSize = trackPoints.size(); + for(int i = 0; i < targetSize; i++){ + double px = trackPoints[i][0]; + double py = trackPoints[i][1]; + + PointXYZ o; + o.x = px; + o.y = py; + o.z = -1.73/2; + targetPoints.push_back(o); + + vector VandYaw; + VandYaw.push_back(0); + VandYaw.push_back(0); + targetVandYaw.push_back(VandYaw); + isStaticVec.push_back(false); + isVisVec.push_back(false); + + VectorXd initMeas = VectorXd(2); + initMeas << px, py; + + UKF ukf; + ukf.Initialize(initMeas, timestamp); + targets_.push_back(ukf); + //initialize trackNumVec + trackNumVec_.push_back(1); + } + timestamp_ = timestamp; + egoPreYaw_ = egoYaw_; + trackManage = trackNumVec_; + init_ = true; + // cout << targets_.size() << " " << trackNumVec_.size() << targetPoints.size()< matchingVec(trackPoints.size()); + // double dt = (timestamp - timestamp_)/1000000.0; + double dt = timestamp - timestamp_; + timestamp_ = timestamp; + + + // start UKF process + int targetSize = targets_.size(); + for(int i = 0; i < targetSize; i++){ + //reset isVisBB_ to false + targets_[i].isVisBB_ = false; + + // making local2local vector + double diffYaw = (egoYaw_ - egoPreYaw_); + double dX = dt*egoVelo_*cos(diffYaw); + double dY = dt*egoVelo_*sin(diffYaw); + VectorXd diff(2); + diff << dX, dY; + targets_[i].local2local_.push_back(diff); + targets_[i].local2localYawVec_.push_back(diffYaw); + + //todo: modify here. This skips irregular measurement and nan + if(trackNumVec_[i] == 0) continue; + // prevent ukf not to explode + if(targets_[i].P_merge_.determinant() > 10 || targets_[i].P_merge_(4,4) > 1000){ + trackNumVec_[i] = 0; + continue; + } + // cout << "target state start -----------------------------------"< measVec; + vector bboxVec; + vector lambdaVec; + // cout << "ProcessIMMUKF" << endl; + targets_[i].ProcessIMMUKF(dt); + // cout << "measurementValidation" << endl; + // pre gating + findMaxZandS(targets_[i], maxDetZ, maxDetS); + maxDetS = maxDetS*4; + double detS = maxDetS.determinant(); + + // prevent ukf not to explode + if(isnan(detS)|| detS > 10) { + trackNumVec_[i] = 0; + continue; + } + + bool secondInit; + if(trackNumVec_[i] == 1){ + secondInit = true; + } + else{ + secondInit = false; + } + + // transform local to The target anchor TF + // redundant calculation, modify here later + vector> dcTrackPoints; + dcTrackPoints = trackPoints; + assert(targets_[i].local2local_.size()== targets_[i].local2localYawVec_.size()); + // transformLocal2TargetAnchorTF(targets_[i].local2local_, targets_[i].local2localYawVec_, dcTrackPoints); + + // measurement gating + measurementValidation(dcTrackPoints, targets_[i], secondInit, maxDetZ, maxDetS, + measVec, bboxVec, matchingVec); + + // bounding box association + // input: track number, bbox measurements, &target + associateBB(trackNumVec_[i], bboxVec, targets_[i]); + + // bounding box validation + updateBB(targets_[i]); + + // cout << "validated meas "< M_PI) targetYaw -= 2.*M_PI; + while (targetYaw<-M_PI) targetYaw += 2.*M_PI; + targets_[i].x_merge_(0) = targets_[i].x_cv_(0) = targets_[i].x_ctrv_(0) = targets_[i].x_rm_(0) = targetX; + targets_[i].x_merge_(1) = targets_[i].x_cv_(1) = targets_[i].x_ctrv_(1) = targets_[i].x_rm_(1) = targetY; + targets_[i].x_merge_(2) = targets_[i].x_cv_(2) = targets_[i].x_ctrv_(2) = targets_[i].x_rm_(2) = targetV; + targets_[i].x_merge_(3) = targets_[i].x_cv_(3) = targets_[i].x_ctrv_(3) = targets_[i].x_rm_(3) = targetYaw; + + trackNumVec_[i]++; + continue; + } + + // update tracking number + if(measVec.size() > 0) { + if(trackNumVec_[i] < 3){ + trackNumVec_[i]++; + } + else if(trackNumVec_[i] == 3){ + trackNumVec_[i] = 5; + } + else if(trackNumVec_[i] >= 5){ + trackNumVec_[i] = 5; + } + }else{ + if(trackNumVec_[i] < 5){ + trackNumVec_[i] = 0; + } + else if(trackNumVec_[i] >= 5 && trackNumVec_[i] < 8){ + trackNumVec_[i]++; + } + else if(trackNumVec_[i] = 8){ + trackNumVec_[i] = 0; + } + } + + if(trackNumVec_[i] == 0) continue; + + + filterPDA(targets_[i], measVec, lambdaVec); + // cout << "PostIMMUKF" << endl; + targets_[i].PostProcessIMMUKF(lambdaVec); + // TODO: might be wrong + double targetVelo = targets_[i].x_merge_(2); + targets_[i].velo_history_.push_back(targetVelo); + if(targets_[i].velo_history_.size() == 4) { + targets_[i].velo_history_.erase (targets_[i].velo_history_.begin()); + } + + // targets_[i].x_cv_(0) = targets_[i].x_ctrv_(0) = targets_[i].x_rm_(0) = targets_[i].x_merge_(0) = measVec[0](0); + // targets_[i].x_cv_(1) = targets_[i].x_ctrv_(1) = targets_[i].x_rm_(1) = targets_[i].x_merge_(1) = measVec[0](1); + } + // end UKF process + + // cout << trackPoints[0][0] << endl; + // cout << targets_[0].x_merge_(0) << endl; + + // deling with over segmentation, update trackNumVec_ + mergeOverSegmentation(targets_); + + + // making new ukf target + int addedNum = 0; + int targetNum = targets_.size(); + int matchSize = matchingVec.size(); + for(int i = 0; i < matchSize; i ++){ + if(matchingVec[i] == 0){ + double px = trackPoints[i][0]; + double py = trackPoints[i][1]; + + VectorXd initMeas = VectorXd(2); + initMeas << px, py; + + UKF ukf; + ukf.Initialize(initMeas, timestamp); + targets_.push_back(ukf); + //initialize trackNumVec + trackNumVec_.push_back(1); + addedNum ++; + } + } + assert(targets_.size() == (addedNum + targetNum)); + + // making poitns for visualization + // cout << "making points for vis" < cp; + cp.push_back(tx); + cp.push_back(ty); + + // update tx and ty to the position in local tf + // transformTargetAnchorTF2Local(targets_[i].local2local_, targets_[i].local2localYawVec_ ,cp); + // cout << "after back to ego tf" << endl; + // cout << cp[0] << " " << cp[1] << endl; + + double tv = targets_[i].x_merge_(2); + double tyaw = targets_[i].x_merge_(3); + + // tyaw += egoPoints_[0][2]; + while (tyaw> M_PI) tyaw -= 2.*M_PI; + while (tyaw<-M_PI) tyaw += 2.*M_PI; + // cout << "testing yaw off "<< tyaw << endl; + + PointXYZ o; + o.x = cp[0]; + o.y = cp[1]; + o.z = -1.73/2; + targetPoints.push_back(o); + + vector VandYaw; + VandYaw.push_back(tv); + VandYaw.push_back(tyaw); + targetVandYaw.push_back(VandYaw); + + isStaticVec.push_back(false); + // isVisVec.push_back(false); + isVisVec.push_back(targets_[i].isVisBB_); + if(targets_[i].isVisBB_){ + visBBs.push_back(targets_[i].BBox_); + } + + if(trackNumVec_[i] != 0){ + targetNumCount ++; + } + } + + // static dynamic classification + targetSize = isStaticVec.size(); + for (int i = 0; i < targetNum; i++){ + // once target is static, it is dtatic until lost + if(targets_[i].isStatic_ ){ + isStaticVec[i] = true; + continue; + } + + + if(trackNumVec_[i] >= 2 && targets_[i].lifetime_ > 8 ){ + // assuming below 0.3 m/s for static onject + double distThres = 0.11 * targets_[i].lifetime_; + distThres = 3.0; + if((targets_[i].distFromInit_ < distThres)&& + (targets_[i].modeProbRM_ > targets_[i].modeProbCV_ || + targets_[i].modeProbRM_ > targets_[i].modeProbCTRV_ )){ + isStaticVec[i] = true; + targets_[i].isStatic_ = true; + } + else{ + + } + } + } + + trackManage = trackNumVec_; + egoPreYaw_ = egoYaw_; +} \ No newline at end of file diff --git a/trlo/src/3d_mot/ukf.cpp b/trlo/src/3d_mot/ukf.cpp new file mode 100644 index 0000000..717e8a6 --- /dev/null +++ b/trlo/src/3d_mot/ukf.cpp @@ -0,0 +1,973 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +#include "3d_mot/ukf.h" +// #include "tools.h" +#include "Eigen/Dense" +#include +#include + +using namespace std; +using namespace Eigen; +//using Eigen::MatrixXd; +//using Eigen::VectorXd; +using std::vector; + +/** +* Initializes Unscented Kalman filter +*/ +UKF::UKF() { + // if this is false, laser measurements will be ignored (except during init) + use_laser_ = true; + + // if this is false, radar measurements will be ignored (except during init) + use_radar_ = true; + + // initial state vector + x_merge_ = MatrixXd(5, 1); + + // initial state vector + x_cv_ = MatrixXd(5, 1); + + // initial state vector + x_ctrv_ = MatrixXd(5, 1); + + // initial state vector + x_rm_ = MatrixXd(5, 1); + + // initial covariance matrix + P_merge_ = MatrixXd(5, 5); + + // initial covariance matrix + P_cv_ = MatrixXd(5, 5); + + // initial covariance matrix + P_ctrv_ = MatrixXd(5, 5); + + // initial covariance matrix + P_rm_ = MatrixXd(5, 5); + + // Process noise standard deviation longitudinal acceleration in m/s^2 + + // std_a_cv_ = 0.8; + // std_a_ctrv_ = 0.8; + // std_a_rm_ = 5; + // std_ctrv_yawdd_ = 0.8; + // std_cv_yawdd_ = 0.8; + // std_rm_yawdd_ = 3; + + + // std_a_cv_ = 2; + // std_a_ctrv_ = 2; + // std_a_rm_ = 5; + // std_ctrv_yawdd_ = 2; + // std_cv_yawdd_ = 2; + // std_rm_yawdd_ = 3; + + std_a_cv_ = 2; + std_a_ctrv_ = 2; + std_a_rm_ = 3; + std_ctrv_yawdd_ = 2; + std_cv_yawdd_ = 2; + std_rm_yawdd_ = 3; + + // std_a_cv_ = 3; + // std_a_ctrv_ = 3; + // std_a_rm_ = 3; + // std_ctrv_yawdd_ = 3; + // std_cv_yawdd_ = 3; + // std_rm_yawdd_ = 3; + + // ------------- not delete here + // std_a_cv_ = 2; + // std_a_ctrv_ = 2; + // std_a_rm_ = 8; + // std_ctrv_yawdd_ = 2; + // std_cv_yawdd_ = 2; + // std_rm_yawdd_ = 3; + //------------------ + // Laser measurement noise standard deviation position1 in m + std_laspx_ = 0.15; + // std_laspx_ = 0.3; + // Laser measurement noise standard deviation position2 in m + std_laspy_ = 0.15; + // std_laspy_ = 0.3; + + // initially set to false, set to true in first call of ProcessMeasurement + is_initialized_ = false; + + // time when the state is true, in us + time_us_ = 0.0; + + // state dimension + n_x_ = 5; + + // Augmented state dimension + n_aug_ = 7; + + // Sigma point spreading parameter + lambda_ = 3 - n_x_; + + // Augmented sigma point spreading parameter + lambda_aug_ = 3 - n_aug_; + + // predicted sigma points matrix +// Xsig_pred_ = MatrixXd(n_x_, 2 * n_aug_ + 1); + + // predicted sigma points matrix + Xsig_pred_cv_ = MatrixXd(n_x_, 2 * n_aug_ + 1); + + // predicted sigma points matrix + Xsig_pred_ctrv_ = MatrixXd(n_x_, 2 * n_aug_ + 1); + + // predicted sigma points matrix + Xsig_pred_rm_ = MatrixXd(n_x_, 2 * n_aug_ + 1); + + //create vector for weights + weights_ = VectorXd(2 * n_aug_ + 1); + + // the current NIS for radar + NIS_radar_ = 0.0; + + // the current NIS for laser + NIS_laser_ = 0.0; + + count_ = 0; + count_empty_ = 0; + + ini_u_.push_back(0.33); + ini_u_.push_back(0.33); + ini_u_.push_back(0.33); + + // different from paper, might be wrong + p1_.push_back(0.9); + p1_.push_back(0.05); + p1_.push_back(0.05); + + p2_.push_back(0.05); + p2_.push_back(0.9); + p2_.push_back(0.05); + + p3_.push_back(0.05); + p3_.push_back(0.05); + p3_.push_back(0.9); + + // p1_.push_back(0.8); + // p1_.push_back(0.1); + // p1_.push_back(0.1); + + // p2_.push_back(0.8); + // p2_.push_back(0.1); + // p2_.push_back(0.1); + + // p3_.push_back(0.1); + // p3_.push_back(0.1); + // p3_.push_back(0.8); + + modeMatchProbCV2CV_ = 0; + modeMatchProbCTRV2CV_ = 0; + modeMatchProbRM2CV_ = 0; + + modeMatchProbCV2CTRV_ = 0; + modeMatchProbCTRV2CTRV_ = 0; + modeMatchProbRM2CTRV_ = 0; + + modeMatchProbCV2RM_ = 0; + modeMatchProbCTRV2RM_ = 0; + modeMatchProbRM2RM_ = 0; + + modeProbCV_ = 0.33; + modeProbCTRV_ = 0.33; + modeProbRM_ = 0.33; + + zPredCVl_ = VectorXd(2); + zPredCTRVl_ = VectorXd(2); + zPredRMl_ = VectorXd(2); + + zPredCVr_ = VectorXd(3); + zPredCTRVr_ = VectorXd(3); + zPredRMr_ = VectorXd(3); + +// lS_ = MatrixXd(2,2); +// rS_ = MatrixXd(3,3); + lS_cv_ = MatrixXd(2,2); + lS_ctrv_ = MatrixXd(2,2); + lS_rm_ = MatrixXd(2,2); + + rS_cv_ = MatrixXd(3,3); + rS_ctrv_ = MatrixXd(3,3); + rS_rm_ = MatrixXd(3,3); + + K_cv_ = MatrixXd(2,2); + K_ctrv_ = MatrixXd(2,2); + K_rm_ = MatrixXd(2,2); + +// NISvals_laser_cv_.open( "../NISvals_laser_cv.txt", ios::out ); +// NISvals_laser_ctrv_.open( "../NISvals_laser_ctrv.txt", ios::out ); +// NISvals_laser_rm_.open( "../NISvals_laser_rm.txt", ios::out ); +// // Check for errors opening the files +// if( !NISvals_laser_cv_.is_open() ) +// { +// cout << "Error opening NISvals_laser.txt" << endl; +// exit(1); +// } + + gammaG_ = 9.21; + pD_ = 0.9; + pG_ = 0.99; + + //track parameter + lifetime_ = 0; + velo_history_; + isStatic_ = false; + + //bounding box params + isVisBB_ = false; + bestYaw_ = 0; + bb_yaw_ = 0; + bb_area_ = 0; + + //for env classification + initMeas_ = VectorXd(2); + distFromInit_ = 0; + + // local2local yaw (t-1 to t) + // local2localYaw_ = 0; + + x_merge_yaw_ = 0; + + + + // globalYaw_ = 0; + // anchorTF_ = VectorXd(2); + + // double gammaG = 4.61; // 90% +// double gammaG = 5.99; // 95% +// double gammaG = 7.38; // 97.5% +// gammaG_ = 9.21; // 99% global variable +} + +UKF::~UKF() { +// NISvals_laser_cv_.close(); +// NISvals_laser_ctrv_.close(); +// NISvals_laser_rm_.close(); +} + +void UKF::Initialize(VectorXd z, double timestamp) { + // first measurement + // x_merge_ << 1, 1, 1, 1, 0.1; + x_merge_ << 1, 1, 0, 0, 0.1; + + // init covariance matrix + // P_merge_ << 0.5, 0, 0, 0, 0, + // 0, 0.5, 0, 0, 0, + // 0, 0, 1, 0, 0, + // 0, 0, 0, 1, 0, + // 0, 0, 0, 0, 1; + + // P_merge_ << 0.5, 0, 0, 0, 0, + // 0, 0.5, 0, 0, 0, + // 0, 0, 3, 0, 0, + // 0, 0, 0, 1, 0, + // 0, 0, 0, 0, 1; + + P_merge_ << 0.5, 0, 0, 0, 0, + 0, 0.5, 0, 0, 0, + 0, 0, 3, 0, 0, + 0, 0, 0,10, 0, + 0, 0, 0, 0, 1; + + // set weights + double weight_0 = lambda_aug_ / (lambda_aug_ + n_aug_); + weights_(0) = weight_0; + for (int i = 1; i < 2 * n_aug_ + 1; i++) { //2n+1 weights + double weight = 0.5 / (n_aug_ + lambda_aug_); + weights_(i) = weight; + } + + // init timestamp + time_us_ = timestamp; + + x_merge_(0) = z(0); + x_merge_(1) = z(1); + + zPredCVl_(0) = z(0); + zPredCVl_(1) = z(1); + + zPredCTRVl_(0) = z(0); + zPredCTRVl_(1) = z(1); + + zPredRMl_(0) = z(0); + zPredRMl_(1) = z(1); + + + x_cv_ = x_ctrv_ = x_rm_ = x_merge_; + P_cv_ = P_ctrv_ = P_rm_ = P_merge_; + + // lS_cv_ << 2, 0, + // 0, 2; + // lS_ctrv_ << 2, 0, + // 0, 2; + // lS_rm_ << 2, 0, + // 0, 2; + lS_cv_ << 1, 0, + 0, 1; + lS_ctrv_ << 1, 0, + 0, 1; + lS_rm_ << 1, 0, + 0, 1; + + // anchorTF_ << 0, 0; +} + +double UKF::CalculateGauss(VectorXd z, int sensorInd, int modelInd){ + if(sensorInd == 0){ + if (modelInd == 0) { + double detS = fabs(lS_cv_.determinant()); + MatrixXd inS = lS_cv_.inverse(); +// cout << z << endl << zPredCVl_ << endl; +// VectorXd s = (z-zPredCVl_).transpose(); +// double a = ((z-zPredCVl_).transpose()*inS*(z-zPredCVl_)); + return exp(-1*(((z-zPredCVl_).transpose()*inS*(z-zPredCVl_))(0))/2)/sqrt(((2*M_PI)*(2*M_PI)*detS)); + } + else if (modelInd == 1) { + double detS = fabs(lS_ctrv_.determinant()); + MatrixXd inS = lS_ctrv_.inverse(); + return exp(-1*(((z-zPredCTRVl_).transpose()*inS*(z-zPredCTRVl_))(0))/2)/sqrt(((2*M_PI)*(2*M_PI)*detS)); + } + else { + double detS = fabs(lS_rm_.determinant()); + MatrixXd inS = lS_rm_.inverse(); + return exp(-1*(((z-zPredRMl_).transpose() *inS*(z-zPredRMl_))(0))/2) /sqrt(((2*M_PI)*(2*M_PI)*detS)); + } + } + else if(sensorInd == 1){ + if (modelInd == 0){ + double detS = fabs(rS_cv_.determinant()); + MatrixXd inS = rS_cv_.inverse(); + double cvProb = exp(-1*(((z-zPredCVr_).transpose() *inS*(z-zPredCVr_))(0))/2) /sqrt((2*M_PI)*(2*M_PI)*(2*M_PI)*detS); + if(cvProb != 0) return cvProb; + else { + z[1] = -1 * z[1]; + cvProb = exp(-1*(((z-zPredCVr_).transpose() *inS*(z-zPredCVr_))(0))/2) /sqrt((2*M_PI)*(2*M_PI)*(2*M_PI)*detS); + return cvProb; + } + } + else if (modelInd == 1) { + double detS = fabs(rS_ctrv_.determinant()); + MatrixXd inS = rS_ctrv_.inverse(); + double ctrvProb = exp(-1 * (((z - zPredCTRVr_).transpose() * inS * (z - zPredCTRVr_))(0)) / 2) / + sqrt((2 * M_PI) * (2 * M_PI) * (2 * M_PI) * detS); + if (ctrvProb != 0) return ctrvProb; + else { + z[1] = -1 * z[1]; + ctrvProb = exp(-1 * (((z - zPredCTRVr_).transpose() * inS * (z - zPredCTRVr_))(0)) / 2) / + sqrt((2 * M_PI) * (2 * M_PI) * (2 * M_PI) * detS); + return ctrvProb; + } + } + else { + double detS = fabs(rS_rm_.determinant()); + MatrixXd inS = rS_rm_.inverse(); + double rmProb = exp(-1*(((z-zPredRMr_).transpose() *inS*(z-zPredRMr_))(0))/2) /sqrt((2*M_PI)*(2*M_PI)*(2*M_PI)*detS); + if(rmProb != 0)return rmProb; + else{ + z[1] = -1 * z[1]; + rmProb = exp(-1*(((z-zPredRMr_).transpose() *inS*(z-zPredRMr_))(0))/2) /sqrt((2*M_PI)*(2*M_PI)*(2*M_PI)*detS); + return rmProb; + } + } + } +} + +void UKF::UpdateModeProb(vector lambdaVec){ + double cvGauss = lambdaVec[0]; + double ctrvGauss = lambdaVec[1]; + double rmGauss = lambdaVec[2]; + double sumGauss = cvGauss*modeProbCV_ + ctrvGauss*modeProbCTRV_ + rmGauss*modeProbRM_; + modeProbCV_ = (cvGauss *modeProbCV_) /sumGauss; + modeProbCTRV_ = (ctrvGauss*modeProbCTRV_)/sumGauss; + modeProbRM_ = (rmGauss *modeProbRM_) /sumGauss; + if(fabs(modeProbCV_) < 0.0001) modeProbCV_ = 0.0001; + if(fabs(modeProbCTRV_) < 0.0001) modeProbCTRV_ = 0.0001; + if(fabs(modeProbRM_) < 0.0001) modeProbRM_ = 0.0001; + + // cout << endl<<"mode prob"< modeProbCTRV_){ + if(modeProbCV_ > modeProbRM_){ + x_merge_yaw_ = x_cv_(3); + } + else{ + x_merge_yaw_ = x_rm_(3); + } + } + else{ + if(modeProbCTRV_ > modeProbRM_){ + x_merge_yaw_ = x_ctrv_(3); + } + else{ + x_merge_yaw_ = x_rm_(3); + } + } + x_merge_(3) = x_merge_yaw_; +} + +void UKF::MergeEstimationAndCovariance(){ + // cout << endl<<"merge x cv" < M_PI) x_merge_(3) -= 2.*M_PI; + while (x_merge_(3)<-M_PI) x_merge_(3) += 2.*M_PI; + + // not interacting yaw(-pi ~ pi) + UpdateYawWithHighProb(); + // cout << "merged yaw " << x_merge_yaw_<< endl; + + P_merge_ = modeProbCV_ *(P_cv_ +(x_cv_ - x_merge_)*(x_cv_ - x_merge_).transpose()) + + modeProbCTRV_*(P_ctrv_ +(x_ctrv_ - x_merge_)*(x_ctrv_ - x_merge_).transpose())+ + modeProbRM_ *(P_rm_ +(x_rm_ - x_merge_)*(x_rm_ - x_merge_).transpose()); + +} + +void UKF::MixingProbability() { + double sumProb1 = modeProbCV_*p1_[0]+modeProbCTRV_*p2_[0]+modeProbRM_*p3_[0]; + double sumProb2 = modeProbCV_*p1_[1]+modeProbCTRV_*p2_[1]+modeProbRM_*p3_[1]; + double sumProb3 = modeProbCV_*p1_[2]+modeProbCTRV_*p2_[2]+modeProbRM_*p3_[2]; + modeMatchProbCV2CV_ = modeProbCV_ *p1_[0]/sumProb1; + modeMatchProbCTRV2CV_ = modeProbCTRV_*p2_[0]/sumProb1; + modeMatchProbRM2CV_ = modeProbRM_ *p3_[0]/sumProb1; + + modeMatchProbCV2CTRV_ = modeProbCV_ *p1_[1]/sumProb2; + modeMatchProbCTRV2CTRV_ = modeProbCTRV_*p2_[1]/sumProb2; + modeMatchProbRM2CTRV_ = modeProbRM_ *p3_[1]/sumProb2; + + modeMatchProbCV2RM_ = modeProbCV_ *p1_[2]/sumProb3; + modeMatchProbCTRV2RM_ = modeProbCTRV_*p2_[2]/sumProb3; + modeMatchProbRM2RM_ = modeProbRM_ *p3_[2]/sumProb3; + +} + + +void UKF::Interaction() { + + MatrixXd x_pre_cv = x_cv_; + MatrixXd x_pre_ctrv = x_ctrv_; + MatrixXd x_pre_rm = x_rm_; + MatrixXd P_pre_cv = P_cv_; + MatrixXd P_pre_ctrv = P_ctrv_; + MatrixXd P_pre_rm = P_rm_; + x_cv_ = modeMatchProbCV2CV_ *x_pre_cv + modeMatchProbCTRV2CV_ *x_pre_ctrv + modeMatchProbRM2CV_ *x_pre_rm; + x_ctrv_ = modeMatchProbCV2CTRV_*x_pre_cv + modeMatchProbCTRV2CTRV_*x_pre_ctrv + modeMatchProbRM2CTRV_*x_pre_rm; + x_rm_ = modeMatchProbCV2RM_ *x_pre_cv + modeMatchProbCTRV2RM_ *x_pre_ctrv + modeMatchProbRM2RM_*x_pre_rm; + + // not interacting yaw(-pi ~ pi) + x_cv_(3) = x_pre_cv(3); + x_ctrv_(3) = x_pre_ctrv(3); + x_rm_(3) = x_pre_rm(3); + +// cout<< "cv x state before interaction: " < M_PI) x_cv_(3) -= 2.*M_PI; + while (x_cv_(3) <-M_PI) x_cv_(3) += 2.*M_PI; + while (x_ctrv_(3)> M_PI) x_ctrv_(3) -= 2.*M_PI; + while (x_ctrv_(3)<-M_PI) x_ctrv_(3) += 2.*M_PI; + while (x_rm_(3) > M_PI) x_rm_(3) -= 2.*M_PI; + while (x_rm_(3) <-M_PI) x_rm_(3) += 2.*M_PI; + + P_cv_ = modeMatchProbCV2CV_ *(P_pre_cv +(x_pre_cv - x_cv_)* (x_pre_cv - x_cv_).transpose()) + + modeMatchProbCTRV2CV_ *(P_pre_ctrv+(x_pre_ctrv -x_cv_)* (x_pre_ctrv -x_cv_).transpose())+ + modeMatchProbRM2CV_ *(P_pre_rm + (x_pre_rm - x_cv_)* (x_pre_rm - x_cv_).transpose()); + P_ctrv_ = modeMatchProbCV2CTRV_ *(P_pre_cv+ (x_pre_cv - x_ctrv_)* (x_pre_cv- x_ctrv_).transpose()) + + modeMatchProbCTRV2CTRV_*(P_pre_ctrv+(x_pre_ctrv -x_ctrv_)* (x_pre_ctrv -x_ctrv_).transpose())+ + modeMatchProbRM2CTRV_ *(P_pre_rm + (x_pre_rm - x_ctrv_)* (x_pre_rm - x_ctrv_).transpose()); + P_rm_ = modeMatchProbCV2RM_ *(P_pre_cv+ (x_pre_cv - x_rm_)* (x_pre_cv - x_rm_).transpose()) + + modeMatchProbCTRV2RM_ *(P_pre_ctrv+(x_pre_ctrv -x_rm_)* (x_pre_ctrv -x_rm_).transpose())+ + modeMatchProbRM2RM_ *(P_pre_rm + (x_pre_rm - x_rm_)* (x_pre_rm - x_rm_).transpose()); + +} + + +/** +* @param {MeasurementPackage} meas_package The latest measurement data of +* either radar or laser. +*/ +void UKF::ProcessIMMUKF(double dt) { + /********************************************************************************************************* + * IMM Mixing and Interaction + *********************************************************************************************************************/ + MixingProbability(); + Interaction(); + /********************************************************************************************************* + * Prediction + *********************************************************************************************************************/ + Prediction(dt, 0); + Prediction(dt, 1); + Prediction(dt, 2); + + /********************************************************************************************************* + * Update + *********************************************************************************************************************/ + UpdateLidar(0); + UpdateLidar(1); + UpdateLidar(2); + +} + +void UKF::PostProcessIMMUKF(vector lambdaVec) { + /********************************************************************************************************* + * IMM Merge Step + *********************************************************************************************************************/ + UpdateModeProb(lambdaVec); + MergeEstimationAndCovariance(); +} + + + +void UKF::Ctrv(double p_x, double p_y, double v, double yaw, double yawd, double nu_a, double nu_yawdd, + double delta_t, vector&state) { + //predicted state values + double px_p, py_p; + + //avoid division by zero + if (fabs(yawd) > 0.001) { + px_p = p_x + v / yawd * (sin(yaw + yawd * delta_t) - sin(yaw)); + py_p = p_y + v / yawd * (cos(yaw) - cos(yaw + yawd * delta_t)); + } + else { + px_p = p_x + v * delta_t * cos(yaw); + py_p = p_y + v * delta_t * sin(yaw); + } + double v_p = v; + double yaw_p = yaw + yawd * delta_t; + double yawd_p = yawd; + + //add noise + px_p = px_p + 0.5 * nu_a * delta_t * delta_t * cos(yaw); + py_p = py_p + 0.5 * nu_a * delta_t * delta_t * sin(yaw); + v_p = v_p + nu_a*delta_t; + + yaw_p = yaw_p + 0.5*nu_yawdd*delta_t*delta_t; + yawd_p = yawd_p + nu_yawdd*delta_t; + + + state[0] = px_p; + state[1] = py_p; + state[2] = v_p; + state[3] = yaw_p; + state[4] = yawd_p; +} + +void UKF::Cv(double p_x, double p_y, double v, double yaw, double yawd, double nu_a, double nu_yawdd, + double delta_t, vector&state) { + //predicted state values + double px_p = p_x + v*cos(yaw)*delta_t; + double py_p = p_y + v*sin(yaw)*delta_t; + + double v_p = v; + // not sure which one, works better in curve by using yaw + double yaw_p = yaw; +// double yaw_p = 0; + double yawd_p = yawd; + + //add noise + px_p = px_p + 0.5 * nu_a * delta_t * delta_t * cos(yaw); + py_p = py_p + 0.5 * nu_a * delta_t * delta_t * sin(yaw); + v_p = v_p + nu_a*delta_t; + + yaw_p = yaw_p + 0.5*nu_yawdd*delta_t*delta_t; + yawd_p = yawd_p + nu_yawdd*delta_t; + + state[0] = px_p; + state[1] = py_p; + state[2] = v_p; + state[3] = yaw_p; + state[4] = yawd_p; + +} + + +void UKF::randomMotion(double p_x, double p_y, double v, double yaw, double yawd, double nu_a, double nu_yawdd, + double delta_t, vector&state) { + // double px_p = p_x + 0.5 * nu_a * delta_t * delta_t * cos(yaw); + // double py_p = p_y + 0.5 * nu_a * delta_t * delta_t * sin(yaw); + // double v_p = v + nu_a*delta_t; + + // double yaw_p = yaw + 0.5*nu_yawdd*delta_t*delta_t; + // double yawd_p = yawd + nu_yawdd*delta_t; + + double px_p = p_x; + double py_p = p_y; + double v_p = v; + + double yaw_p = yaw; + double yawd_p = yawd; + + state[0] = px_p; + state[1] = py_p; + state[2] = v_p; + state[3] = yaw_p; + state[4] = yawd_p; +} + +/** +* Predicts sigma points, the state, and the state covariance matrix. +* @param {double} delta_t the change in time (in seconds) between the last +* measurement and this one. +*/ +void UKF::Prediction(double delta_t, int modelInd) { + /********************************************************************************************************* + * Initialize model parameters + *********************************************************************************************************************/ + double std_yawdd, std_a; + MatrixXd x_(x_cv_.rows(), 1); + MatrixXd P_(P_cv_.rows(),P_cv_.cols()); + MatrixXd Xsig_pred_(Xsig_pred_cv_.rows(), Xsig_pred_cv_.cols()); + if(modelInd == 0){ + x_ = x_cv_.col(0); + P_ = P_cv_; + Xsig_pred_ = Xsig_pred_cv_; + std_yawdd = std_cv_yawdd_; + std_a = std_a_cv_; + } + else if(modelInd == 1){ + x_ = x_ctrv_.col(0); + P_ = P_ctrv_; + Xsig_pred_ = Xsig_pred_ctrv_; + std_yawdd = std_ctrv_yawdd_; + std_a = std_a_ctrv_; + } + else{ + x_ = x_rm_.col(0); + P_ = P_rm_; + Xsig_pred_ = Xsig_pred_rm_; + std_yawdd = std_rm_yawdd_; + std_a = std_a_rm_; + } + + /********************************************************************************************************* + * Generate Sigma Points + *********************************************************************************************************************/ + //calculate square root of P + MatrixXd A = P_.llt().matrixL(); + + /********************************************************************************************************* + * Augment Sigma Points + *********************************************************************************************************************/ + //create augmented mean vector + VectorXd x_aug = VectorXd(n_aug_); + + //create augmented state covariance + MatrixXd P_aug = MatrixXd(n_aug_, n_aug_); + + //create sigma point matrix + MatrixXd Xsig_aug = MatrixXd(n_aug_, 2 * n_aug_ + 1); + + //create augmented mean state + x_aug.head(5) = x_; + x_aug(5) = 0; + x_aug(6) = 0; + + //create augmented covariance matrix + P_aug.fill(0.0); + P_aug.topLeftCorner(5, 5) = P_; + P_aug(5, 5) = std_a*std_a; + P_aug(6, 6) = std_yawdd*std_yawdd; + + //create square root matrix + MatrixXd L = P_aug.llt().matrixL(); + + //create augmented sigma points + Xsig_aug.col(0) = x_aug; +// if(modelInd == 2) cout<< "x state: "< state(5); + if(modelInd == 0) Cv(p_x, p_y, v, yaw, yawd, nu_a, nu_yawdd, delta_t, state); + else if(modelInd == 1) Ctrv(p_x, p_y, v, yaw, yawd, nu_a, nu_yawdd, delta_t, state); + else randomMotion(p_x, p_y, v, yaw, yawd, nu_a, nu_yawdd, delta_t, state); + + //write predicted sigma point into right column + Xsig_pred_(0, i) = state[0]; + Xsig_pred_(1, i) = state[1]; + Xsig_pred_(2, i) = state[2]; + Xsig_pred_(3, i) = state[3]; + Xsig_pred_(4, i) = state[4]; + } +// if(modelInd == 2) cout<< "predicted sigma x points: "< M_PI) x_(3) -= 2.*M_PI; + while (x_(3)<-M_PI) x_(3) += 2.*M_PI; + //predicted state covariance matrix + P_.fill(0.0); + for (int i = 0; i < 2 * n_aug_ + 1; i++) { //iterate over sigma points + // state difference + VectorXd x_diff = Xsig_pred_.col(i) - x_; + //angle normalization + while (x_diff(3)> M_PI) x_diff(3) -= 2.*M_PI; + while (x_diff(3)<-M_PI) x_diff(3) += 2.*M_PI; + P_ = P_ + weights_(i) * x_diff * x_diff.transpose(); + } + + /********************************************************************************************************* + * Update model parameters + *********************************************************************************************************************/ + if(modelInd == 0){ + x_cv_.col(0) = x_; + P_cv_ = P_; + Xsig_pred_cv_ = Xsig_pred_; + } + else if(modelInd == 1){ + x_ctrv_.col(0) = x_; + P_ctrv_ = P_; + Xsig_pred_ctrv_ = Xsig_pred_; + } + else{ + x_rm_.col(0) = x_; + P_rm_ = P_; + Xsig_pred_rm_ = Xsig_pred_; + } +} + +/** +* Updates the state and the state covariance matrix using a laser measurement. +* @param {MeasurementPackage} meas_package +*/ +void UKF::UpdateLidar(int modelInd) { + // TODO refactoring + /********************************************************************************************************* + * Initialize model parameters + *********************************************************************************************************************/ + VectorXd x(x_cv_.rows()); + MatrixXd P(P_cv_.rows(),P_cv_.cols()); + MatrixXd Xsig_pred(Xsig_pred_cv_.rows(), Xsig_pred_cv_.cols()); + if(modelInd == 0){ + x = x_cv_.col(0); + P = P_cv_; + Xsig_pred = Xsig_pred_cv_; + } + else if(modelInd == 1){ + x = x_ctrv_.col(0); + P = P_ctrv_; + Xsig_pred = Xsig_pred_ctrv_; + } + else{ + x = x_rm_.col(0); + P = P_rm_; + Xsig_pred = Xsig_pred_rm_; + } + +// count_++; + //extract measurement as VectorXd + // VectorXd z = meas_package.raw_measurements_; + //set measurement dimension, lidar can measure p_x and p_y + int n_z = 2; + + //create matrix for sigma points in measurement space + MatrixXd Zsig = MatrixXd(n_z, 2 * n_aug_ + 1); + + //transform sigma points into measurement space + for (int i = 0; i < 2 * n_aug_ + 1; i++) { //2n+1 simga points + + // extract values for better readibility + double p_x = Xsig_pred(0, i); + double p_y = Xsig_pred(1, i); + + // measurement model + Zsig(0, i) = p_x; + Zsig(1, i) = p_y; + } + + //mean predicted measurement + VectorXd z_pred = VectorXd(n_z); + z_pred.fill(0.0); + for (int i = 0; i < 2 * n_aug_ + 1; i++) { + z_pred = z_pred + weights_(i) * Zsig.col(i); + } + + //measurement covariance matrix S + MatrixXd S = MatrixXd(n_z, n_z); + S.fill(0.0); + for (int i = 0; i < 2 * n_aug_ + 1; i++) { //2n+1 simga points + //residual + VectorXd z_diff = Zsig.col(i) - z_pred; + S = S + weights_(i) * z_diff * z_diff.transpose(); + } + + //add measurement noise covariance matrix + MatrixXd R = MatrixXd(n_z, n_z); + R << std_laspx_*std_laspx_, 0, + 0, std_laspy_*std_laspy_; + S = S + R; + + //create matrix for cross correlation Tc + MatrixXd Tc = MatrixXd(n_x_, n_z); + + /********************************************************************************************************* + * UKF Update for Lidar + *********************************************************************************************************************/ + //calculate cross correlation matrix + Tc.fill(0.0); + for (int i = 0; i < 2 * n_aug_ + 1; i++) { //2n+1 simga points + + //residual + VectorXd z_diff = Zsig.col(i) - z_pred; + // state difference + VectorXd x_diff = Xsig_pred.col(i) - x; + + Tc = Tc + weights_(i) * x_diff * z_diff.transpose(); + } + + //Kalman gain K; + MatrixXd K = Tc * S.inverse(); + + // //residual + // VectorXd z_diff = z - z_pred; + + // //update state mean and covariance matrix + // x = x + K * z_diff; + // P = P - K*S*K.transpose(); + + // while (x(3)> M_PI) x(3) -= 2.*M_PI; + // while (x(3)<-M_PI) x(3) += 2.*M_PI; + /********************************************************************************************************* + * Update model parameters + *********************************************************************************************************************/ + if(modelInd == 0){ + x_cv_.col(0) = x; + P_cv_ = P; + Xsig_pred_cv_ = Xsig_pred; + zPredCVl_ = z_pred; + lS_cv_ = S; + K_cv_ = K; + } + else if(modelInd == 1){ + x_ctrv_.col(0) = x; + P_ctrv_ = P; + Xsig_pred_ctrv_ = Xsig_pred; + zPredCTRVl_ = z_pred; + lS_ctrv_ = S; + K_ctrv_ = K; + } + else{ + x_rm_.col(0) = x; + P_rm_ = P; + Xsig_pred_rm_ = Xsig_pred; + zPredRMl_ = z_pred; + lS_rm_ = S; + K_rm_ = K; + } +} + +void UKF::PDAupdate(vector z, int modelInd){ + VectorXd z_pred; + MatrixXd S, x_, P_, K; + if(modelInd == 0){ + z_pred = zPredCVl_; + S = lS_cv_; + x_ = x_cv_; + P_ = P_cv_; + K = K_cv_; + } + else if(modelInd == 1){ + z_pred = zPredCTRVl_; + S = lS_ctrv_; + x_ = x_ctrv_; + P_ = P_ctrv_; + K = K_ctrv_; + } + else{ + z_pred = zPredRMl_; + S = lS_rm_; + x_ = x_rm_; + P_ = P_rm_; + K = K_rm_; + } + + int numMeas = z.size(); + double unitV = M_PI; +// double valiV = unitV*sqrt(gammaG_*) + double b = (2*M_PI*numMeas*(1-pD_*pG_))/(gammaG_*unitV*pD_); + + //residual + VectorXd z_diff = z[0] - z_pred; + + //calculate NIS + NIS_laser_ = z_diff.transpose() * S.inverse() * z_diff; + + //update state mean and covariance matrix + x_ = x_ + K * z_diff; + P_ = P_ - K*S*K.transpose(); + + while (x_(3)> M_PI) x_(3) -= 2.*M_PI; + while (x_(3)<-M_PI) x_(3) += 2.*M_PI; + + /********************************************************************************************************* + * Update model parameters + *********************************************************************************************************************/ + if(modelInd == 0){ + x_cv_.col(0) = x_; + P_cv_ = P_; +// NISvals_laser_cv_ << NIS_laser_ << endl; +// cout << "cv nis: "<< NIS_laser_ << endl; + } + else if(modelInd == 1){ + x_ctrv_.col(0) = x_; + P_ctrv_ = P_; +// NISvals_laser_ctrv_ << NIS_laser_ << endl; +// cout << "ctrv nis: "<< NIS_laser_ << endl; + } + else{ + x_rm_.col(0) = x_; + P_rm_ = P_; +// NISvals_laser_rm_ << NIS_laser_ << endl; +// cout << "x rm after update: "<) + +会生成一个安装命令,执行: +``` +wget https://developer.download.nvidia.com/compute/cuda/12.4.0/local_installers/cuda_12.4.0_550.54.14_linux.run +sudo sh cuda_12.4.0_550.54.14_linux.run +``` + +取消cuda自带的驱动: +![alt text](image.png) + +3. 添加环境变量: +``` +gedit ~/.bashrc +#添加以下内容: +export CUDA_HOME=/usr/local/cuda-11.3 +export LD_LIBRARY_PATH=${CUDA_HOME}/lib64 +export PATH=${CUDA_HOME}/bin:${PATH} +``` + +4. 测试是否安装成功: +``` +nvcc -V +``` + +5. 卸载命令: +``` +# cuda10.1及以上的卸载 +cd /usr/local/cuda-xx.x/bin/ +sudo ./cuda-uninstaller +sudo rm -rf /usr/local/cuda-xx.x +``` + +### cuDNN 8.2.1 + +1. 安装cuDNN 8.2.1 + +进入[官网](https://developer.nvidia.com/rdp/cudnn-archive) +![alt text](image-1.png) + +按顺序安装,因为有依赖关系: +``` +sudo dpkg -i libcudnn8_8.2.1.32-1+cuda11.3_amd64.deb +sudo dpkg -i libcudnn8_8.2.1.32-1+cuda11.3_amd64.deb +sudo dpkg -i libcudnn8-samples_8.2.1.32-1+cuda11.3_amd64.deb +``` + +2. 测试是否安装成功: +``` +cp -r /usr/src/cudnn_samples_v8/ $HOME # 将cuDNN例子复制到可写路径中 +​ +cd ~/cudnn_samples_v8/mnistCUDNN # 转到可写路径 +​ +sudo make clean # 编译文件 +sudo make +​ +sudo ./mnistCUDNN # 运行样例程序 +``` + +如果报错显示缺少库(缺少#include "FreeImage.h),就安装依赖: +``` +sudo apt-get install libfreeimage3 libfreeimage-dev +``` + +### 安装Oenpcdet的环境 + +1. 创建虚拟环境 +``` +conda create -n dear_dlo python=3.8 +``` + +激活虚拟环境 +``` +conda activate dear_dlo +``` + +2. 安装Pytorch1.10.0 + torchvision0.11.0 + torchaudio0.10.0 +``` +pip install torch==1.10.0+cu113 torchvision==0.11.0+cu113 torchaudio==0.10.0 -f https://download.pytorch.org/whl/torch_stable.html +conda install cudatoolkit=11.3 + +#以清华源为例,下载的时候会报错,因为cudatoolkit=11.3的版本在清华源上是没有的。尝试用北外的源下载11.3版本的cudatoolkit。 +conda install cudatoolkit=11.3 -c https://mirrors.bfsu.edu.cn/anaconda/cloud/conda-forge +``` + +测试Pytorch是否可用: +``` +python +import torch as t +device = t.device('cuda' if t.cuda.is_available() else 'cpu') +print(device) +``` + +如果不是cuda请检查pytorch是否安装为cpu版本 + +3. 安装spconv: +``` +pip install spconv-cu113 -i https://pypi.tuna.tsinghua.edu.cn/simple +``` + +验证spconv是否可用: +``` +import spconv.pytorch as spconv +``` + +4. 下载安装Openpcdet + +**建议直接将其下载到虚拟环境中(~/anaconda3/envs/dear_dlo)** +``` +~/anaconda3/envs/dear_dlo +git clone https://github.com/open-mmlab/OpenPCDet.git +cd OpenPCDet +pip install -r requirements.txt +sudo python setup.py develop +``` + +测试是否可用: +``` +cd tools +python demo.py --cfg_file cfgs/kitti_models/pv_rcnn.yaml --ckpt pointpillar_7728.pth --data_path 000000.bin +``` + + + + + + +==**到此为止,PointPillars和Center-PointPillars的python版本应该都可以使用了,接下来是TensorRT版本的部署,因为我要把它们嵌入到dlo中**== + + + + + + +## 三、tensorRT-8.5.3.1 + +1. 安装tensorRT-8.5.3.1 + +进入[官网](https://developer.nvidia.com/nvidia-tensorrt-8x-download) + +选择“TensorRT 8.5 GA Update 2 for Linux x86_64 and CUDA 11.0, 11.1, 11.2, 11.3, 11.4, 11.5, 11.6, 11.7 and 11.8 TAR Package”下载 + +下载完成后是一个名字为“TensorRT-8.5.3.1.Linux.x86_64-gnu.cuda-11.8.cudnn8.6.tar.gz”的压缩包 + +解压: +``` +tar zxvf TensorRT-8.5.3.1.Linux.x86_64-gnu.cuda-11.8.cudnn8.6.tar.gz +``` + +添加环境: +``` +gedit ~/.bashrc +# 添加以下内容 +# tensorrt environment +export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/home/jyp/3rdparty/TensorRT-8.5.3.1/lib # TensorRT-8.5.3.1/lib前面一长串是你的安装路径 +export CPATH=/home/jyp/3rdparty/TensorRT-8.5.3.1/include:$CPATH # TensorRT-8.5.3.1/include前面一长串是你的安装路径 +``` + +2. 附带软件安装 + +把附带的软件装了,不然使用时可能会报错: + +以python为例: +``` +cd TensorRT-8.5.3.1/python +pip install tensorrt-8.5.3.1-cp38-none-linux_x86_64.whl # 选择对应版本的python +``` + +其他: +``` +# 安装 pyyaml scikit-image onnx onnx-simplifier +pip install pyyaml scikit-image onnx onnx-simplifier + +# 安装onnx-graphsurgeon +pip install onnx_graphsurgeon --index-url https://pypi.ngc.nvidia.com +``` + +查看onnx相关环境: +``` +pip list | grep onnx +``` + +显示如下: +onnx 1.14.0 +onnx-graphsurgeon 0.3.27 +onnx-simplifier 0.4.33 +onnxruntime 1.15.1 + + +# Center_Pointpillars TensorRT部署 + +1. 下载Lidar_AI_Solution(内包含Cneter_Pointpillars源码) + +``` +git clone --recursive https://github.com/NVIDIA-AI-IOT/Lidar_AI_Solution.git +``` + +2. 修改配置文件 +``` +cd Lidar_AI_Solution/CUDA-CenterPoint +gedit tools/build.trt.sh +``` + +在大概23行的位置添加以下内容: +``` +# TensorRT-8.5.3.1路径 +export PATH=/home/jyp/3rdparty/TensorRT-8.5.3.1/bin:$PATH +export LD_LIBRARY_PATH=/home/jyp/3rdparty/TensorRT-8.5.3.1/lib:$LD_LIBRARY_PATH +export LIBRARY_PATH=/home/jyp/3rdparty/TensorRT-8.5.3.1/lib:$LIBRARY_PATH + +# cuda路径, 按照自己的修改 +export CUDA_Lib=/usr/local/cuda-11.3/lib64 +export CUDA_Inc=/usr/local/cuda-11.3/include +export CUDA_Bin=/usr/local/cuda-11.3/bin +export CUDA_HOME=/usr/local/cuda-11.3 + +#cudnn路径, 安装cuda已经将cudnn的lib64放入了cuda/lib64里面 +export CUDNN_Lib=/usr/local/cuda-11.3/lib64 + + +trt_version=8513 +``` + +另外还有: +``` +# if 语句中运行trtexec可执行文件改成绝对路径, +# 这句trtexec运行作用是在使用TensorRT-8.5.3.1/bin/下trtexec程序生成engine文件 +# 需要在CUDA-CenterPoint目录运行tool/build.trt.sh, 不能在tool运行build.trt.sh +# 应该修改的绝对路径如下: +/home/jyp/3rdparty/TensorRT-8.5.3.1/bin/trtexec +``` + +**但是实际我没修改也成功了,可能是配置了TensorRT的环境变量自动识别到了** + +3. 运行转换脚本 +``` +bash tool/build.trt.sh +# 终端显示如下,转换的时候时间比较长,如果1-2秒就结束了,代表没转换成功, 可以看看前面的修改正确吗 +# 转换后会在model文件夹中生成3个新文件。 +Building the model: model/rpn_centerhead_sim.plan.8531, this will take 2 minutes. Wait a moment 🤗🤗🤗~. +``` + +运行后tool/build.trt.sh,在./model路径下,总共5个文件: + +原本有centerpoint.scn.onnx与rpn_centerhead_sim.onnx两个onnx文件,生成一个rpn_centerhead_sim.plan和2个log文件,目录如下: +``` +model + ├── centerpoint.scn.onnx + ├── rpn_centerhead_sim.8531.log + ├── rpn_centerhead_sim.onnx + ├── rpn_centerhead_sim.plan -> ... + └── rpn_centerhead_sim.plan.8531 +``` + +4. 编译 +``` +mkdir -p build && cd build +cmake .. && make -j +``` + +5. 运行 +``` +cd build +./centerpoint ../data/test/ --verbose +``` + +出现以下结果表示成功: +``` +<<<<<<<<<<< +load file: ../data/test/291e7331922541cea98122b607d24831.bin +find points num: 239911 +[TIME] Voxelization: 0.12720 ms +valid_num: 85179 +[TIME] 3D Backbone: 2.22150 ms +[TIME] RPN + Head: 1.49750 ms +[TIME] Decode + NMS: 2.27770 ms +Detection NUM: 194 +Saved prediction in: ../data/prediction/291e7331922541cea98122b607d24831.txt +``` + +# ROS noetic安装 + +1. 添加ROS软件源 +``` +sudo sh -c '. /etc/lsb-release && echo "deb http://mirrors.ustc.edu.cn/ros/ubuntu/ $DISTRIB_CODENAME main" > /etc/apt/sources.list.d/ros-latest.list' +``` + +2. 添加密钥 +``` +sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 +``` + +3. 更新软甲源 +``` +sudo apt update +``` + +4. 安装ROS +``` +sudo apt install ros-noetic-desktop-full +``` + +5. 初始化rosdep +``` +sudo apt-get install python3-pip +sudo pip install rosdepc +sudo rosdepc init +rosdepc update +``` + +6. 配置环境变量 +``` +echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc +source ~/.bashrc +``` + +7. 安装rosinstall +``` +sudo apt install python3-rosinstall python3-rosinstall-generator python3-wstool +``` + +8. 检查是否安装成功 +``` +roscore +rosrun turtlesim turtlesim_node +rosrun turtlesim turtle_teleop_key +``` + + + + +==**至此全部环境已经配置完毕!可以编译功能包了!**== + +# 运行dear_dlo + +``` +cd dear_dlo_ws +catkin_make +sourse devel/setup.bash +roslaunch dear_dlo dear_dlo.launch +``` + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/trlo/src/center_pointpillars/centerpoint.cpp b/trlo/src/center_pointpillars/centerpoint.cpp new file mode 100644 index 0000000..2301891 --- /dev/null +++ b/trlo/src/center_pointpillars/centerpoint.cpp @@ -0,0 +1,247 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#include "center_pointpillars/centerpoint.h" +#include +#include +#include +#include +#include "NvInfer.h" +#include "NvOnnxConfig.h" +#include "NvInferRuntime.h" +#include "center_pointpillars/timer.hpp" + +#include +#include +#include +#include + +template +double getAverage(std::vector const& v) { + if (v.empty()) { + return 0; + } + return std::accumulate(v.begin(), v.end(), 0.0) / v.size(); +} + +CenterPoint::CenterPoint(std::string modelFile_Dir, bool verbose): verbose_(verbose) +{ + trt_ = TensorRT::load(modelFile_Dir + "rpn_centerhead_sim.plan"); + if(trt_ == nullptr) abort(); + + pre_.reset(new PreProcessCuda()); + post_.reset(new PostProcessCuda()); + + scn_engine_ = spconv::load_engine_from_onnx(modelFile_Dir + "centerpoint.scn.onnx"); + + checkCudaErrors(cudaMallocHost((void **)&h_detections_num_, sizeof(unsigned int))); + checkCudaErrors(cudaMemset(h_detections_num_, 0, sizeof(unsigned int))); + + checkCudaErrors(cudaMalloc((void **)&d_detections_, MAX_DET_NUM * DET_CHANNEL * sizeof(float))); + checkCudaErrors(cudaMemset(d_detections_, 0, MAX_DET_NUM * DET_CHANNEL * sizeof(float))); + + //add d_detections_reshape_ + checkCudaErrors(cudaMalloc((void **)&d_detections_reshape_, MAX_DET_NUM * DET_CHANNEL * sizeof(float))); + checkCudaErrors(cudaMemset(d_detections_reshape_, 0, MAX_DET_NUM * DET_CHANNEL * sizeof(float))); + + detections_.resize(MAX_DET_NUM, {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}); + + for(unsigned int i=0; i < NUM_TASKS; i++) { + checkCudaErrors(cudaMalloc((void **)&d_reg_[i], trt_->getBindingNumel("reg_" + std::to_string(i)) * sizeof(half))); + checkCudaErrors(cudaMalloc((void **)&d_height_[i], trt_->getBindingNumel("height_" + std::to_string(i)) * sizeof(half))); + checkCudaErrors(cudaMalloc((void **)&d_dim_[i], trt_->getBindingNumel("dim_" + std::to_string(i)) * sizeof(half))); + checkCudaErrors(cudaMalloc((void **)&d_rot_[i], trt_->getBindingNumel("rot_" + std::to_string(i)) * sizeof(half))); + checkCudaErrors(cudaMalloc((void **)&d_vel_[i], trt_->getBindingNumel("vel_" + std::to_string(i)) * sizeof(half))); + checkCudaErrors(cudaMalloc((void **)&d_hm_[i], trt_->getBindingNumel("hm_" + std::to_string(i)) * sizeof(half))); + + if(i==0){ + auto d = trt_->getBindingDims("reg_" + std::to_string(i)); + reg_n_ = d[0]; + reg_c_ = d[1]; + reg_h_ = d[2]; + reg_w_ = d[3]; + + d = trt_->getBindingDims("height_" + std::to_string(i)); + height_c_ = d[1]; + d = trt_->getBindingDims("dim_" + std::to_string(i)); + dim_c_ = d[1]; + d = trt_->getBindingDims("rot_" + std::to_string(i)); + rot_c_ = d[1]; + d = trt_->getBindingDims("vel_" + std::to_string(i)); + vel_c_ = d[1]; + } + auto d = trt_->getBindingDims("hm_" + std::to_string(i)); + hm_c_[i] = d[1]; + } + h_mask_size_ = params_.nms_pre_max_size * DIVUP(params_.nms_pre_max_size, NMS_THREADS_PER_BLOCK) * sizeof(uint64_t); + checkCudaErrors(cudaMallocHost((void **)&h_mask_, h_mask_size_)); + checkCudaErrors(cudaMemset(h_mask_, 0, h_mask_size_)); + return; +} + +CenterPoint::~CenterPoint(void) +{ + pre_.reset(); + trt_.reset(); + post_.reset(); + scn_engine_.reset(); + + checkCudaErrors(cudaFreeHost(h_detections_num_)); + checkCudaErrors(cudaFree(d_detections_)); + checkCudaErrors(cudaFree(d_detections_reshape_)); + + for (unsigned int i=0; i < NUM_TASKS; i++) { + checkCudaErrors(cudaFree(d_reg_[i])); + checkCudaErrors(cudaFree(d_height_[i])); + checkCudaErrors(cudaFree(d_dim_[i])); + checkCudaErrors(cudaFree(d_rot_[i])); + checkCudaErrors(cudaFree(d_vel_[i])); + checkCudaErrors(cudaFree(d_hm_[i])); + } + + checkCudaErrors(cudaFreeHost(h_mask_)); + return; +} + +int CenterPoint::prepare(){ + pre_->alloc_resource(); + return 0; +} + +int CenterPoint::doinfer(void* points, unsigned int point_num, cudaStream_t stream) +{ + float elapsedTime = 0.0f; + + timer_.start(stream); + pre_->generateVoxels((float *)points, point_num, stream); + timing_pre_.push_back(timer_.stop("Voxelization", verbose_)); + + unsigned int valid_num = pre_->getOutput(&d_voxel_features, &d_voxel_indices, sparse_shape); + if (verbose_) { + std::cout << "valid_num: " << valid_num <forward( + {valid_num, 5}, spconv::DType::Float16, d_voxel_features, + {valid_num, 4}, spconv::DType::Int32, d_voxel_indices, + 1, sparse_shape, stream + ); + timing_scn_engine_.push_back(timer_.stop("3D Backbone", verbose_)); + + timer_.start(stream); + trt_->forward({result->features_data(), d_reg_[0], d_height_[0], d_dim_[0], d_rot_[0], d_vel_[0], d_hm_[0], + d_reg_[1], d_height_[1], d_dim_[1], d_rot_[1], d_vel_[1], d_hm_[1], + d_reg_[2], d_height_[2], d_dim_[2], d_rot_[2], d_vel_[2], d_hm_[2], + d_reg_[3], d_height_[3], d_dim_[3], d_rot_[3], d_vel_[3], d_hm_[3], + d_reg_[4], d_height_[4], d_dim_[4], d_rot_[4], d_vel_[4], d_hm_[4], + d_reg_[5], d_height_[5], d_dim_[5], d_rot_[5], d_vel_[5], d_hm_[5]}, stream); + timing_trt_.push_back(timer_.stop("RPN + Head", verbose_)); + nms_pred_.clear(); + + timer_.start(stream); + for(unsigned int i_task =0; i_task < NUM_TASKS; i_task++) { + checkCudaErrors(cudaMemset(h_detections_num_, 0, sizeof(unsigned int))); + checkCudaErrors(cudaMemset(d_detections_, 0, MAX_DET_NUM * DET_CHANNEL * sizeof(float))); + checkCudaErrors(cudaMemset(d_detections_reshape_, 0, MAX_DET_NUM * DET_CHANNEL * sizeof(float))); + + post_->doPostDecodeCuda(reg_n_, reg_h_, reg_w_, reg_c_, height_c_, dim_c_, rot_c_, vel_c_, hm_c_[i_task], + d_reg_[i_task], + d_height_[i_task], + d_dim_[i_task], + d_rot_[i_task], + d_vel_[i_task], + d_hm_[i_task], + h_detections_num_, + d_detections_, stream); + if(*h_detections_num_ == 0) continue; + + checkCudaErrors(cudaMemcpyAsync(detections_.data(), d_detections_, MAX_DET_NUM * DET_CHANNEL * sizeof(float), cudaMemcpyDeviceToHost, stream)); + checkCudaErrors(cudaStreamSynchronize(stream)); + + std::sort(detections_.begin(), detections_.end(), + [](float11 boxes1, float11 boxes2) { return boxes1.val[10] > boxes2.val[10]; }); + + checkCudaErrors(cudaMemcpyAsync(d_detections_, detections_.data() , MAX_DET_NUM * DET_CHANNEL * sizeof(float), cudaMemcpyHostToDevice, stream)); + checkCudaErrors(cudaMemsetAsync(h_mask_, 0, h_mask_size_, stream)); + + post_->doPermuteCuda(*h_detections_num_, d_detections_, d_detections_reshape_, stream); + checkCudaErrors(cudaStreamSynchronize(stream)); + + post_->doPostNMSCuda(*h_detections_num_, d_detections_reshape_, h_mask_, stream); + checkCudaErrors(cudaStreamSynchronize(stream)); + + int col_blocks = DIVUP(*h_detections_num_, NMS_THREADS_PER_BLOCK); + std::vector remv(col_blocks, 0); + std::vector keep(*h_detections_num_, false); + int max_keep_size = 0; + for (unsigned int i_nms = 0; i_nms < *h_detections_num_; i_nms++) { + unsigned int nblock = i_nms / NMS_THREADS_PER_BLOCK; + unsigned int inblock = i_nms % NMS_THREADS_PER_BLOCK; + + if (!(remv[nblock] & (1ULL << inblock))) { + keep[i_nms] = true; + if (max_keep_size++ < params_.nms_post_max_size) { + nms_pred_.push_back(Bndbox(detections_[i_nms].val[0], detections_[i_nms].val[1], detections_[i_nms].val[2], + detections_[i_nms].val[3], detections_[i_nms].val[4], detections_[i_nms].val[5], + detections_[i_nms].val[6], detections_[i_nms].val[7], detections_[i_nms].val[8], + params_.task_num_stride[i_task] + static_cast(detections_[i_nms].val[9]), detections_[i_nms].val[10])); + } + uint64_t* p = h_mask_ + i_nms * col_blocks; + for (int j_nms = nblock; j_nms < col_blocks; j_nms++) { + remv[j_nms] |= p[j_nms]; + } + } + } + } + timing_post_.push_back(timer_.stop("Decode + NMS", verbose_)); + if (verbose_) { + std::cout << "Detection NUM: " << nms_pred_.size() << std::endl; + // for(int loop = 0; loop +#include + +PostProcessCuda::PostProcessCuda() +{ + checkCudaErrors(cudaMalloc((void **)&d_post_center_range_, 6 * sizeof(float))); + checkCudaErrors(cudaMalloc((void **)&d_voxel_size_, 2 * sizeof(float))); + checkCudaErrors(cudaMalloc((void **)&d_pc_range_, 2 * sizeof(float))); + + checkCudaErrors(cudaMemcpy(d_post_center_range_, params_.post_center_range, 6 * sizeof(float), cudaMemcpyHostToDevice)); + checkCudaErrors(cudaMemcpy(d_voxel_size_, params_.voxel_size, 2 * sizeof(float), cudaMemcpyHostToDevice)); + checkCudaErrors(cudaMemcpy(d_pc_range_, params_.pc_range, 2 * sizeof(float), cudaMemcpyHostToDevice)); + return; +} + +PostProcessCuda::~PostProcessCuda() +{ + checkCudaErrors(cudaFree(d_post_center_range_)); + checkCudaErrors(cudaFree(d_voxel_size_)); + checkCudaErrors(cudaFree(d_pc_range_)); + return; +} + +int PostProcessCuda::doPostDecodeCuda( + int N, + int H, + int W, + int C_reg, + int C_height, + int C_dim, + int C_rot, + int C_vel, + int C_hm, + const half *reg, + const half *height, + const half *dim, + const half *rot, + const half *vel, + const half *hm, + unsigned int *detection_num, + float *detections, cudaStream_t stream) +{ + postprocess_launch( + N, + H, + W, + C_reg, + C_height, + C_dim, + C_rot, + C_vel, + C_hm, + reg, + height, + dim, + rot, + vel, + hm, + detection_num, + detections, + d_post_center_range_, + params_.out_size_factor, + d_voxel_size_, + d_pc_range_, + params_.score_threshold, + stream + ); + return 0; +} + +int PostProcessCuda::doPostNMSCuda( + unsigned int boxes_num, + float *boxes_sorted, + uint64_t* mask, cudaStream_t stream) +{ + if(boxes_num > params_.nms_pre_max_size){ + std::cerr << "[ERR] Boxs num exceeds:" << params_.nms_pre_max_size << std::endl; + // exit(-1); + } + + nms_launch(boxes_num, boxes_sorted, params_.nms_iou_threshold, mask, stream); + return 0; +} + +int PostProcessCuda::doPermuteCuda( + unsigned int boxes_num, + const float *boxes_sorted, + float * permute_boxes, cudaStream_t stream) +{ + + if(boxes_num > params_.nms_pre_max_size){ + std::cerr << "[ERR] Boxs num exceeds:" << params_.nms_pre_max_size << std::endl; + // exit(-1); + } + + permute_launch(boxes_num, boxes_sorted, permute_boxes, stream); + return 0; +} diff --git a/trlo/src/center_pointpillars/postprocess_kernels.cu b/trlo/src/center_pointpillars/postprocess_kernels.cu new file mode 100644 index 0000000..76b1e96 --- /dev/null +++ b/trlo/src/center_pointpillars/postprocess_kernels.cu @@ -0,0 +1,412 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#include "center_pointpillars/kernel.h" + +#define HALF_PI (3.141592653 * 0.5) + +__global__ void predictKernel( + int N, + int H, + int W, + int C_reg, + int C_height, + int C_dim, + int C_rot, + int C_vel, + int C_hm, + const half *reg, + const half *height, + const half *dim, + const half *rot, + const half *vel, + const half *hm, + unsigned int *detection_num, + float *detections, + const float *post_center_range, + float out_size_factor, + const float *voxel_size, + const float *pc_range, + float score_threshold) +{ + int x = blockIdx.x * blockDim.x + threadIdx.x; + + if(x >= H * W) return; + + int HW = H * W; + int h = x / W; + int w = x % W; + + for (int n = 0; n < N; n++) { + + int label = 0; + float score = 1 / (1 + exp(-__half2float(hm[n * 0 * HW + 0 * HW + h * W + w]))); + + for (int i = 1; i < C_hm; i++) { + float sco = 1 / (1 + exp(-__half2float(hm[n * C_hm * HW + i * HW + h * W + w]))); + if (sco > score) { + label = i; + score = sco; + } + } + + if(score < score_threshold) continue; + + auto xs = __half2float(reg[n * C_reg * HW + h * W + w]) + w; + auto ys = __half2float(reg[n * C_reg * HW + HW + h * W + w]) + h; + + xs = xs * out_size_factor * voxel_size[0] + pc_range[0]; + ys = ys * out_size_factor * voxel_size[1] + pc_range[1]; + + auto zs = __half2float(height[n * C_height * HW + h * W + w]); + + if(xs < post_center_range[0] || xs > post_center_range[3]) continue; + if(ys < post_center_range[1] || ys > post_center_range[4]) continue; + if(zs < post_center_range[2] || zs > post_center_range[5]) continue; + + unsigned int curDet = 0; + curDet = atomicAdd(detection_num, 1); + + if(curDet >= MAX_DET_NUM){ + *detection_num = MAX_DET_NUM; + continue; + } + + float3 dim_; + dim_.x = exp(__half2float(dim[n * C_dim * HW + 0 * HW + h * W + w])); + dim_.y = exp(__half2float(dim[n * C_dim * HW + 1 * HW + h * W + w])); + dim_.z = exp(__half2float(dim[n * C_dim * HW + 2 * HW + h * W + w])); + + auto vx = __half2float(vel[n * C_vel * HW + 0 * HW + h * W + w]); + auto vy = __half2float(vel[n * C_vel * HW + 1 * HW + h * W + w]); + auto rs = atan2(__half2float(rot[n * C_rot * HW + h * W + w]), __half2float(rot[n * C_rot * HW + HW + h * W + w])); + + *(float3 *)(&detections[n * MAX_DET_NUM * DET_CHANNEL + DET_CHANNEL * curDet + 0]) = make_float3(xs, ys, zs); + *(float3 *)(&detections[n * MAX_DET_NUM * DET_CHANNEL + DET_CHANNEL * curDet + 3]) = dim_; + detections[n * MAX_DET_NUM * DET_CHANNEL + DET_CHANNEL * curDet + 6] = vx; + detections[n * MAX_DET_NUM * DET_CHANNEL + DET_CHANNEL * curDet + 7] = vy; + *(float3 *)(&detections[n * MAX_DET_NUM * DET_CHANNEL + DET_CHANNEL * curDet + 8]) = make_float3(rs, label, score); + } +} + +__device__ inline float cross(const float2 p1, const float2 p2, const float2 p0) { + return (p1.x - p0.x) * (p2.y - p0.y) - (p2.x - p0.x) * (p1.y - p0.y); +} + +__device__ inline int check_box2d(float const *const box, const float2 p) { + const float MARGIN = 1e-2; + float center_x = box[0]; + float center_y = box[1]; + float angle_cos = cos(-box[6]); + float angle_sin = sin(-box[6]); + float rot_x = (p.x - center_x) * angle_cos + (p.y - center_y) * (-angle_sin); + float rot_y = (p.x - center_x) * angle_sin + (p.y - center_y) * angle_cos; + + return (fabs(rot_x) < box[3] / 2 + MARGIN && fabs(rot_y) < box[4] / 2 + MARGIN); +} + +__device__ inline bool intersection(const float2 p1, const float2 p0, const float2 q1, const float2 q0, float2 &ans) { + + if (( fmin(p0.x, p1.x) <= fmax(q0.x, q1.x) && + fmin(q0.x, q1.x) <= fmax(p0.x, p1.x) && + fmin(p0.y, p1.y) <= fmax(q0.y, q1.y) && + fmin(q0.y, q1.y) <= fmax(p0.y, p1.y) ) == 0) + return false; + + + float s1 = cross(q0, p1, p0); + float s2 = cross(p1, q1, p0); + float s3 = cross(p0, q1, q0); + float s4 = cross(q1, p1, q0); + + if (!(s1 * s2 > 0 && s3 * s4 > 0)) + return false; + + float s5 = cross(q1, p1, p0); + if (fabs(s5 - s1) > 1e-8) { + ans.x = (s5 * q0.x - s1 * q1.x) / (s5 - s1); + ans.y = (s5 * q0.y - s1 * q1.y) / (s5 - s1); + + } else { + float a0 = p0.y - p1.y, b0 = p1.x - p0.x, c0 = p0.x * p1.y - p1.x * p0.y; + float a1 = q0.y - q1.y, b1 = q1.x - q0.x, c1 = q0.x * q1.y - q1.x * q0.y; + float D = a0 * b1 - a1 * b0; + + ans.x = (b0 * c1 - b1 * c0) / D; + ans.y = (a1 * c0 - a0 * c1) / D; + } + + return true; +} + +__device__ inline void rotate_around_center(const float2 ¢er, const float angle_cos, const float angle_sin, float2 &p) { + float new_x = (p.x - center.x) * angle_cos + (p.y - center.y) * (-angle_sin) + center.x; + float new_y = (p.x - center.x) * angle_sin + (p.y - center.y) * angle_cos + center.y; + p = float2 {new_x, new_y}; + return; +} + +__device__ inline bool devIoU(float const *const box_a, float const *const box_b, const float nms_thresh) { + float a_angle = box_a[6], b_angle = box_b[6]; + float a_dx_half = box_a[3] / 2, b_dx_half = box_b[3] / 2, a_dy_half = box_a[4] / 2, b_dy_half = box_b[4] / 2; + float a_x1 = box_a[0] - a_dx_half, a_y1 = box_a[1] - a_dy_half; + float a_x2 = box_a[0] + a_dx_half, a_y2 = box_a[1] + a_dy_half; + float b_x1 = box_b[0] - b_dx_half, b_y1 = box_b[1] - b_dy_half; + float b_x2 = box_b[0] + b_dx_half, b_y2 = box_b[1] + b_dy_half; + float2 box_a_corners[5]; + float2 box_b_corners[5]; + + float2 center_a = float2 {box_a[0], box_a[1]}; + float2 center_b = float2 {box_b[0], box_b[1]}; + + float2 cross_points[16]; + float2 poly_center = {0, 0}; + int cnt = 0; + bool flag = false; + + box_a_corners[0] = float2 {a_x1, a_y1}; + box_a_corners[1] = float2 {a_x2, a_y1}; + box_a_corners[2] = float2 {a_x2, a_y2}; + box_a_corners[3] = float2 {a_x1, a_y2}; + + box_b_corners[0] = float2 {b_x1, b_y1}; + box_b_corners[1] = float2 {b_x2, b_y1}; + box_b_corners[2] = float2 {b_x2, b_y2}; + box_b_corners[3] = float2 {b_x1, b_y2}; + + float a_angle_cos = cos(a_angle), a_angle_sin = sin(a_angle); + float b_angle_cos = cos(b_angle), b_angle_sin = sin(b_angle); + + for (int k = 0; k < 4; k++) { + rotate_around_center(center_a, a_angle_cos, a_angle_sin, box_a_corners[k]); + rotate_around_center(center_b, b_angle_cos, b_angle_sin, box_b_corners[k]); + } + + box_a_corners[4] = box_a_corners[0]; + box_b_corners[4] = box_b_corners[0]; + + for (int i = 0; i < 4; i++) { + for (int j = 0; j < 4; j++) { + flag = intersection(box_a_corners[i + 1], box_a_corners[i], + box_b_corners[j + 1], box_b_corners[j], + cross_points[cnt]); + if (flag) { + poly_center = {poly_center.x + cross_points[cnt].x, poly_center.y + cross_points[cnt].y}; + cnt++; + } + } + } + + for (int k = 0; k < 4; k++) { + if (check_box2d(box_a, box_b_corners[k])) { + poly_center = {poly_center.x + box_b_corners[k].x, poly_center.y + box_b_corners[k].y}; + cross_points[cnt] = box_b_corners[k]; + cnt++; + } + if (check_box2d(box_b, box_a_corners[k])) { + poly_center = {poly_center.x + box_a_corners[k].x, poly_center.y + box_a_corners[k].y}; + cross_points[cnt] = box_a_corners[k]; + cnt++; + } + } + + poly_center.x /= cnt; + poly_center.y /= cnt; + + float2 temp; + for (int j = 0; j < cnt - 1; j++) { + for (int i = 0; i < cnt - j - 1; i++) { + if (atan2(cross_points[i].y - poly_center.y, cross_points[i].x - poly_center.x) > + atan2(cross_points[i+1].y - poly_center.y, cross_points[i+1].x - poly_center.x) + ) { + temp = cross_points[i]; + cross_points[i] = cross_points[i + 1]; + cross_points[i + 1] = temp; + } + } + } + + float area = 0; + for (int k = 0; k < cnt - 1; k++) { + float2 a = {cross_points[k].x - cross_points[0].x, + cross_points[k].y - cross_points[0].y}; + float2 b = {cross_points[k + 1].x - cross_points[0].x, + cross_points[k + 1].y - cross_points[0].y}; + area += (a.x * b.y - a.y * b.x); + } + + float s_overlap = fabs(area) / 2.0;; + float sa = box_a[3] * box_a[4]; + float sb = box_b[3] * box_b[4]; + float iou = s_overlap / fmaxf(sa + sb - s_overlap, 1e-8); + + return iou >= nms_thresh; +} + +__global__ void nms_cuda(const int n_boxes, const float iou_threshold, const float *dev_boxes, uint64_t *dev_mask) { + const int row_start = blockIdx.y; + const int col_start = blockIdx.x; + const int tid = threadIdx.x; + + if (row_start > col_start) return; + + const int row_size = fminf(n_boxes - row_start * NMS_THREADS_PER_BLOCK, NMS_THREADS_PER_BLOCK); + const int col_size = fminf(n_boxes - col_start * NMS_THREADS_PER_BLOCK, NMS_THREADS_PER_BLOCK); + + __shared__ float block_boxes[NMS_THREADS_PER_BLOCK * 7]; + + if (tid < col_size) { + block_boxes[tid * 7 + 0] = dev_boxes[(NMS_THREADS_PER_BLOCK * col_start + tid) * DET_CHANNEL + 0]; + block_boxes[tid * 7 + 1] = dev_boxes[(NMS_THREADS_PER_BLOCK * col_start + tid) * DET_CHANNEL + 1]; + block_boxes[tid * 7 + 2] = dev_boxes[(NMS_THREADS_PER_BLOCK * col_start + tid) * DET_CHANNEL + 2]; + block_boxes[tid * 7 + 3] = dev_boxes[(NMS_THREADS_PER_BLOCK * col_start + tid) * DET_CHANNEL + 3]; + block_boxes[tid * 7 + 4] = dev_boxes[(NMS_THREADS_PER_BLOCK * col_start + tid) * DET_CHANNEL + 4]; + block_boxes[tid * 7 + 5] = dev_boxes[(NMS_THREADS_PER_BLOCK * col_start + tid) * DET_CHANNEL + 5]; + block_boxes[tid * 7 + 6] = dev_boxes[(NMS_THREADS_PER_BLOCK * col_start + tid) * DET_CHANNEL + 6]; + } + __syncthreads(); + + if (tid < row_size) { + const int cur_box_idx = NMS_THREADS_PER_BLOCK * row_start + tid; + const float *cur_box = dev_boxes + cur_box_idx * DET_CHANNEL; + int i = 0; + uint64_t t = 0; + int start = 0; + if (row_start == col_start) { + start = tid + 1; + } + for (i = start; i < col_size; i++) { + if (devIoU(cur_box, block_boxes + i * 7, iou_threshold)) { + t |= 1ULL << i; + } + } + dev_mask[cur_box_idx * gridDim.y + col_start] = t; + } +} + +int postprocess_launch( + int N, + int H, + int W, + int C_reg, + int C_height, + int C_dim, + int C_rot, + int C_vel, + int C_hm, + const half *reg, + const half *height, + const half *dim, + const half *rot, + const half *vel, + const half *hm, + unsigned int *detection_num, + float *detections, + const float *post_center_range, + float out_size_factor, + const float *voxel_size, + const float *pc_range, + float score_threshold, + cudaStream_t stream) +{ + dim3 threads(32); + dim3 blocks(H * W + threads.x - 1/ threads.x); + + predictKernel<<>>(N, H, W, C_reg, C_height, C_dim, C_rot, C_vel, C_hm, + reg, height, dim, rot, vel, hm, detection_num, detections, + post_center_range, out_size_factor, voxel_size, pc_range, + score_threshold); + cudaStreamSynchronize(stream); + auto err = cudaGetLastError(); + if (cudaSuccess != err) { + fprintf(stderr, "CUDA kernel failed : %s\n", cudaGetErrorString(err)); + return -1; + } + + return 0; +} + +int nms_launch(unsigned int boxes_num, + float *boxes_sorted, + float nms_iou_threshold, + uint64_t* mask, + cudaStream_t stream) +{ + int col_blocks = DIVUP(boxes_num, NMS_THREADS_PER_BLOCK); + + dim3 blocks(col_blocks, col_blocks); + dim3 threads(NMS_THREADS_PER_BLOCK); + + nms_cuda<<>>(boxes_num, nms_iou_threshold, boxes_sorted, mask); + cudaStreamSynchronize(stream); + + auto err = cudaGetLastError(); + if (cudaSuccess != err) { + fprintf(stderr, "CUDA kernel failed : %s\n", cudaGetErrorString(err)); + return -1; + } + + return 0; +} + +__global__ void permute_cuda(const float *boxes_sorted, + float * permute_boxes_sorted, int boxes_num){ + + const int tid = threadIdx.x; + if(tid < boxes_num){ + permute_boxes_sorted[tid * DET_CHANNEL + 0] = boxes_sorted[tid * DET_CHANNEL + 0]; + permute_boxes_sorted[tid * DET_CHANNEL + 1] = boxes_sorted[tid * DET_CHANNEL + 1]; + permute_boxes_sorted[tid * DET_CHANNEL + 2] = boxes_sorted[tid * DET_CHANNEL + 2]; + permute_boxes_sorted[tid * DET_CHANNEL + 3] = boxes_sorted[tid * DET_CHANNEL + 4]; + permute_boxes_sorted[tid * DET_CHANNEL + 4] = boxes_sorted[tid * DET_CHANNEL + 3]; + permute_boxes_sorted[tid * DET_CHANNEL + 5] = boxes_sorted[tid * DET_CHANNEL + 5]; + permute_boxes_sorted[tid * DET_CHANNEL + 6] = -boxes_sorted[tid * DET_CHANNEL + 8] - HALF_PI; + } +} + +int permute_launch(unsigned int boxes_num, + const float *boxes_sorted, + float * permute_boxes_sorted, + cudaStream_t stream) +{ + dim3 blocks(1); + dim3 threads(boxes_num); + permute_cuda<<>>(boxes_sorted, permute_boxes_sorted, boxes_num); + cudaStreamSynchronize(stream); + + auto err = cudaGetLastError(); + if (cudaSuccess != err) { + fprintf(stderr, "CUDA kernel failed : %s\n", cudaGetErrorString(err)); + return -1; + } + + return 0; +} \ No newline at end of file diff --git a/trlo/src/center_pointpillars/preprocess.cpp b/trlo/src/center_pointpillars/preprocess.cpp new file mode 100644 index 0000000..6c73d3b --- /dev/null +++ b/trlo/src/center_pointpillars/preprocess.cpp @@ -0,0 +1,118 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#include "center_pointpillars/preprocess.h" +#include +#include + +PreProcessCuda::PreProcessCuda() +{} + +PreProcessCuda::~PreProcessCuda() +{ + checkCudaErrors(cudaFree(hash_table_)); + checkCudaErrors(cudaFree(voxels_temp_)); + + checkCudaErrors(cudaFree(d_voxel_features_)); + checkCudaErrors(cudaFree(d_voxel_num_)); + checkCudaErrors(cudaFree(d_voxel_indices_)); + + checkCudaErrors(cudaFree(d_real_num_voxels_)); + checkCudaErrors(cudaFreeHost(h_real_num_voxels_)); +} + +unsigned int PreProcessCuda::getOutput(half** d_voxel_features, unsigned int** d_voxel_indices, std::vector& sparse_shape){ + *d_voxel_features = d_voxel_features_; + *d_voxel_indices = d_voxel_indices_; + + sparse_shape.clear(); + sparse_shape.push_back(params_.getGridZSize() + 1); + sparse_shape.push_back(params_.getGridYSize()); + sparse_shape.push_back(params_.getGridXSize()); + + return *h_real_num_voxels_; +} + +int PreProcessCuda::alloc_resource(){ + hash_table_size_ = MAX_POINTS_NUM * 2 * 2 * sizeof(unsigned int); + + voxels_temp_size_ = params_.max_voxels * params_.max_points_per_voxel * params_.feature_num * sizeof(float); + voxel_features_size_ = params_.max_voxels * params_.max_points_per_voxel * params_.feature_num * sizeof(half); + + checkCudaErrors(cudaMallocManaged((void **)&hash_table_, hash_table_size_)); + checkCudaErrors(cudaMallocManaged((void **)&voxels_temp_, voxels_temp_size_)); + + voxel_num_size_ = params_.max_voxels * sizeof(unsigned int); + voxel_idxs_size_ = params_.max_voxels * 4 * sizeof(unsigned int); + + checkCudaErrors(cudaMallocManaged((void **)&d_voxel_features_, voxel_features_size_)); + checkCudaErrors(cudaMallocManaged((void **)&d_voxel_num_, voxel_num_size_)); + checkCudaErrors(cudaMallocManaged((void **)&d_voxel_indices_, voxel_idxs_size_)); + checkCudaErrors(cudaMalloc((void **)&d_real_num_voxels_, sizeof(unsigned int))); + checkCudaErrors(cudaMallocHost((void **)&h_real_num_voxels_, sizeof(unsigned int))); + + checkCudaErrors(cudaMemset(d_voxel_num_, 0, voxel_num_size_)); + checkCudaErrors(cudaMemset(d_voxel_features_, 0, voxel_features_size_)); + checkCudaErrors(cudaMemset(d_voxel_indices_, 0, voxel_idxs_size_)); + checkCudaErrors(cudaMemset(d_real_num_voxels_, 0, sizeof(unsigned int))); + + return 0; +} + +int PreProcessCuda::generateVoxels(const float *points, size_t points_size, cudaStream_t stream) +{ + // flash memory for every run + checkCudaErrors(cudaMemsetAsync(hash_table_, 0xff, hash_table_size_, stream)); + checkCudaErrors(cudaMemsetAsync(voxels_temp_, 0xff, voxels_temp_size_, stream)); + + checkCudaErrors(cudaMemsetAsync(d_voxel_num_, 0, voxel_num_size_, stream)); + checkCudaErrors(cudaMemsetAsync(d_real_num_voxels_, 0, sizeof(unsigned int), stream)); + checkCudaErrors(cudaStreamSynchronize(stream)); + + checkCudaErrors(voxelizationLaunch(points, points_size, + params_.min_x_range, params_.max_x_range, + params_.min_y_range, params_.max_y_range, + params_.min_z_range, params_.max_z_range, + params_.pillar_x_size, params_.pillar_y_size, params_.pillar_z_size, + params_.getGridYSize(), params_.getGridXSize(), params_.feature_num, params_.max_voxels, + params_.max_points_per_voxel, hash_table_, + d_voxel_num_, /*d_voxel_features_*/voxels_temp_, d_voxel_indices_, + d_real_num_voxels_, stream)); + checkCudaErrors(cudaMemcpyAsync(h_real_num_voxels_, d_real_num_voxels_, sizeof(int), cudaMemcpyDeviceToHost, stream)); + checkCudaErrors(cudaStreamSynchronize(stream)); + + checkCudaErrors(featureExtractionLaunch(voxels_temp_, d_voxel_num_, + *h_real_num_voxels_, params_.max_points_per_voxel, params_.feature_num, + d_voxel_features_, stream)); + + checkCudaErrors(cudaStreamSynchronize(stream)); + return 0; +} \ No newline at end of file diff --git a/trlo/src/center_pointpillars/preprocess_kernels.cu b/trlo/src/center_pointpillars/preprocess_kernels.cu new file mode 100644 index 0000000..b7810fa --- /dev/null +++ b/trlo/src/center_pointpillars/preprocess_kernels.cu @@ -0,0 +1,230 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#include "center_pointpillars/kernel.h" + +__device__ inline uint64_t hash(uint64_t k) { + k ^= k >> 16; + k *= 0x85ebca6b; + k ^= k >> 13; + k *= 0xc2b2ae35; + k ^= k >> 16; + return k; +} + +__device__ inline void insertHashTable(const uint32_t key, uint32_t *value, + const uint32_t hash_size, uint32_t *hash_table) { + uint64_t hash_value = hash(key); + uint32_t slot = hash_value % (hash_size / 2)/*key, value*/; + uint32_t empty_key = UINT32_MAX; + while (true) { + uint32_t pre_key = atomicCAS(hash_table + slot, empty_key, key); + if (pre_key == empty_key) { + hash_table[slot + hash_size / 2 /*offset*/] = atomicAdd(value, 1); + break; + } else if (pre_key == key) { + break; + } + slot = (slot + 1) % (hash_size / 2); + } +} + +__device__ inline uint32_t lookupHashTable(const uint32_t key, const uint32_t hash_size, const uint32_t *hash_table) { + uint64_t hash_value = hash(key); + uint32_t slot = hash_value % (hash_size / 2)/*key, value*/; + uint32_t empty_key = UINT32_MAX; + int cnt = 0; + while (cnt < 100 /* need to be adjusted according to data*/) { + cnt++; + if (hash_table[slot] == key) { + return hash_table[slot + hash_size / 2]; + } else if (hash_table[slot] == empty_key) { + return empty_key; + } else { + slot = (slot + 1) % (hash_size / 2); + } + } + return empty_key; +} + +__global__ void buildHashKernel(const float *points, size_t points_size, + float min_x_range, float max_x_range, + float min_y_range, float max_y_range, + float min_z_range, float max_z_range, + float voxel_x_size, float voxel_y_size, float voxel_z_size, + int grid_y_size, int grid_x_size, int feature_num, + unsigned int *hash_table, unsigned int *real_voxel_num) { + int point_idx = blockIdx.x * blockDim.x + threadIdx.x; + if (point_idx >= points_size) { + return; + } + + float px = points[feature_num * point_idx]; + float py = points[feature_num * point_idx + 1]; + float pz = points[feature_num * point_idx + 2]; + + if( px < min_x_range || px >= max_x_range || py < min_y_range || py >= max_y_range + || pz < min_z_range || pz >= max_z_range) { + return; + } + + unsigned int voxel_idx = floorf((px - min_x_range) / voxel_x_size); + unsigned int voxel_idy = floorf((py - min_y_range) / voxel_y_size); + unsigned int voxel_idz = floorf((pz - min_z_range) / voxel_z_size); + unsigned int voxel_offset = voxel_idz * grid_y_size * grid_x_size + + voxel_idy * grid_x_size + + voxel_idx; + insertHashTable(voxel_offset, real_voxel_num, points_size * 2 * 2, hash_table); +} + +__global__ void voxelizationKernel(const float *points, size_t points_size, + float min_x_range, float max_x_range, + float min_y_range, float max_y_range, + float min_z_range, float max_z_range, + float voxel_x_size, float voxel_y_size, float voxel_z_size, + int grid_y_size, int grid_x_size, int feature_num, int max_voxels, + int max_points_per_voxel, + unsigned int *hash_table, unsigned int *num_points_per_voxel, + float *voxels_temp, unsigned int *voxel_indices, unsigned int *real_voxel_num) { + int point_idx = blockIdx.x * blockDim.x + threadIdx.x; + if (point_idx >= points_size) { + return; + } + + float px = points[feature_num * point_idx]; + float py = points[feature_num * point_idx + 1]; + float pz = points[feature_num * point_idx + 2]; + + if( px < min_x_range || px >= max_x_range || py < min_y_range || py >= max_y_range + || pz < min_z_range || pz >= max_z_range) { + return; + } + + unsigned int voxel_idx = floorf((px - min_x_range) / voxel_x_size); + unsigned int voxel_idy = floorf((py - min_y_range) / voxel_y_size); + unsigned int voxel_idz = floorf((pz - min_z_range) / voxel_z_size); + unsigned int voxel_offset = voxel_idz * grid_y_size * grid_x_size + + voxel_idy * grid_x_size + + voxel_idx; + + // scatter to voxels + unsigned int voxel_id = lookupHashTable(voxel_offset, points_size * 2 * 2, hash_table); + if (voxel_id >= max_voxels) { + return; + } + + unsigned int current_num = atomicAdd(num_points_per_voxel + voxel_id, 1); + if (current_num < max_points_per_voxel) { + unsigned int dst_offset = voxel_id * (feature_num * max_points_per_voxel) + current_num * feature_num; + unsigned int src_offset = point_idx * feature_num; + for (int feature_idx = 0; feature_idx < feature_num; ++feature_idx) { + voxels_temp[dst_offset + feature_idx] = points[src_offset + feature_idx]; + } + + // now only deal with batch_size = 1 + // since not sure what the input format will be if batch size > 1 + uint4 idx = {0, voxel_idz, voxel_idy, voxel_idx}; + ((uint4 *)voxel_indices)[voxel_id] = idx; + + } +} + +__global__ void featureExtractionKernel(float *voxels_temp, + unsigned int *num_points_per_voxel, + int max_points_per_voxel, int feature_num, half *voxel_features) { + int voxel_idx = blockIdx.x * blockDim.x + threadIdx.x; + num_points_per_voxel[voxel_idx] = num_points_per_voxel[voxel_idx] > max_points_per_voxel ? + max_points_per_voxel : num_points_per_voxel[voxel_idx]; + int valid_points_num = num_points_per_voxel[voxel_idx]; + int offset = voxel_idx * max_points_per_voxel * feature_num; + for (int feature_idx = 0; feature_idx< feature_num; ++feature_idx) { + for (int point_idx = 0; point_idx < valid_points_num - 1; ++point_idx) { + voxels_temp[offset + feature_idx] += voxels_temp[offset + (point_idx + 1) * feature_num + feature_idx]; + } + voxels_temp[offset + feature_idx] /= valid_points_num; + } + + // move to be continuous + for (int feature_idx = 0; feature_idx < feature_num; ++feature_idx) { + int dst_offset = voxel_idx * feature_num; + int src_offset = voxel_idx * feature_num * max_points_per_voxel; + voxel_features[dst_offset + feature_idx] = __float2half(voxels_temp[src_offset + feature_idx]); + } +} + +cudaError_t featureExtractionLaunch(float *voxels_temp, unsigned int *num_points_per_voxel, + const unsigned int real_voxel_num, int max_points_per_voxel, int feature_num, + half *voxel_features, cudaStream_t stream) +{ + int threadNum = THREADS_FOR_VOXEL; + dim3 blocks((real_voxel_num + threadNum - 1) / threadNum); + dim3 threads(threadNum); + featureExtractionKernel<<>> + (voxels_temp, num_points_per_voxel, + max_points_per_voxel, feature_num, voxel_features); + cudaError_t err = cudaGetLastError(); + return err; +} + +cudaError_t voxelizationLaunch(const float *points, size_t points_size, + float min_x_range, float max_x_range, + float min_y_range, float max_y_range, + float min_z_range, float max_z_range, + float voxel_x_size, float voxel_y_size, float voxel_z_size, + int grid_y_size, int grid_x_size, int feature_num, int max_voxels, + int max_points_per_voxel, + unsigned int *hash_table, unsigned int *num_points_per_voxel, + float *voxel_features, unsigned int *voxel_indices, + unsigned int *real_voxel_num, cudaStream_t stream) +{ + int threadNum = THREADS_FOR_VOXEL; + dim3 blocks((points_size+threadNum-1)/threadNum); + dim3 threads(threadNum); + buildHashKernel<<>> + (points, points_size, + min_x_range, max_x_range, + min_y_range, max_y_range, + min_z_range, max_z_range, + voxel_x_size, voxel_y_size, voxel_z_size, + grid_y_size, grid_x_size, feature_num, hash_table, + real_voxel_num); + voxelizationKernel<<>> + (points, points_size, + min_x_range, max_x_range, + min_y_range, max_y_range, + min_z_range, max_z_range, + voxel_x_size, voxel_y_size, voxel_z_size, + grid_y_size, grid_x_size, feature_num, max_voxels, + max_points_per_voxel, hash_table, + num_points_per_voxel, voxel_features, voxel_indices, real_voxel_num); + cudaError_t err = cudaGetLastError(); + return err; +} \ No newline at end of file diff --git a/trlo/src/center_pointpillars/tensorrt.cpp b/trlo/src/center_pointpillars/tensorrt.cpp new file mode 100644 index 0000000..99b00a8 --- /dev/null +++ b/trlo/src/center_pointpillars/tensorrt.cpp @@ -0,0 +1,202 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ +/* + * SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. + * SPDX-License-Identifier: MIT + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL + * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER + * DEALINGS IN THE SOFTWARE. + */ + +#include "center_pointpillars/tensorrt.hpp" +#include +#include "NvInfer.h" +#include "NvInferRuntime.h" +#include +#include +#include +#include +#include + +namespace TensorRT{ + +static class Logger : public nvinfer1::ILogger { + public: + void log(Severity severity, const char* msg) noexcept override { + if (severity == Severity::kERROR || severity == Severity::kINTERNAL_ERROR){ + std::cerr << "[NVINFER LOG]: " << msg << std::endl; + } + } +}gLogger_; + +static std::string format_shape(const nvinfer1::Dims& shape){ + + char buf[200] = {0}; + char* p = buf; + for(int i = 0; i < shape.nbDims; ++i){ + if(i + 1 < shape.nbDims) + p += sprintf(p, "%d x ", shape.d[i]); + else + p += sprintf(p, "%d", shape.d[i]); + } + return buf; +} + +static std::vector load_file(const std::string& file){ + + std::ifstream in(file, std::ios::in | std::ios::binary); + if (!in.is_open()) + return {}; + + in.seekg(0, std::ios::end); + size_t length = in.tellg(); + + std::vector data; + if (length > 0){ + in.seekg(0, std::ios::beg); + data.resize(length); + + in.read((char*)&data[0], length); + } + in.close(); + return data; +} + +static const char* data_type_string(nvinfer1::DataType dt){ + switch(dt){ + case nvinfer1::DataType::kFLOAT: return "Float32"; + case nvinfer1::DataType::kHALF: return "Float16"; + case nvinfer1::DataType::kINT32: return "Int32"; + // case nvinfer1::DataType::kUINT8: return "UInt8"; + case nvinfer1::DataType::kINT8: return "Int8"; + case nvinfer1::DataType::kBOOL: return "BOOL"; + default: return "Unknow"; + } +} + +class EngineImpl : public Engine{ +public: + nvinfer1::IExecutionContext* context_ = nullptr; + nvinfer1::ICudaEngine* engine_ = nullptr; + nvinfer1::IRuntime* runtime_ = nullptr; + + virtual ~EngineImpl(){ + if(context_) context_->destroy(); + if(engine_) engine_->destroy(); + if(runtime_) runtime_->destroy(); + } + + bool load(const std::string& file){ + + auto data = load_file(file); + if(data.empty()){ + printf("Load engine %s failed.\n", file.c_str()); + return false; + } + + runtime_ = nvinfer1::createInferRuntime(gLogger_); + if(runtime_ == nullptr){ + printf("Failed to create runtime.\n"); + return false; + } + + engine_ = runtime_->deserializeCudaEngine(data.data(), data.size(), 0); + if(engine_ == nullptr){ + printf("Failed to deserial CUDAEngine.\n"); + return false; + } + + context_ = engine_->createExecutionContext(); + if(context_ == nullptr){ + printf("Failed to create execution context.\n"); + return false; + } + return true; + } + + virtual int64_t getBindingNumel(const std::string& name) override{ + nvinfer1::Dims d = engine_->getBindingDimensions(engine_->getBindingIndex(name.c_str())); + return std::accumulate(d.d, d.d + d.nbDims, 1, std::multiplies()); + } + + virtual std::vector getBindingDims(const std::string& name) override{ + nvinfer1::Dims dims = engine_->getBindingDimensions(engine_->getBindingIndex(name.c_str())); + std::vector output(dims.nbDims); + std::transform(dims.d, dims.d + dims.nbDims, output.begin(), [](int32_t v){return v;}); + return output; + } + + virtual bool forward(const std::initializer_list& buffers, void* stream = nullptr) override{ + return context_->enqueueV2(buffers.begin(), (cudaStream_t)stream, nullptr); + } + + virtual void print() override{ + + if(!context_){ + printf("Infer print, nullptr.\n"); + return; + } + + int numInput = 0; + int numOutput = 0; + for(int i = 0; i < engine_->getNbBindings(); ++i){ + if(engine_->bindingIsInput(i)) + numInput++; + else + numOutput++; + } + + printf("Engine %p detail\n", this); + printf("Inputs: %d\n", numInput); + for(int i = 0; i < numInput; ++i){ + int ibinding = i; + printf("\t%d.%s : \tshape {%s}, %s\n", + i, + engine_->getBindingName(ibinding), + format_shape(engine_->getBindingDimensions(ibinding)).c_str(), + data_type_string(engine_->getBindingDataType(ibinding)) + ); + } + + printf("Outputs: %d\n", numOutput); + for(int i = 0; i < numOutput; ++i){ + int ibinding = i + numInput; + printf("\t%d.%s : \tshape {%s}, %s\n", + i, + engine_->getBindingName(ibinding), + format_shape(engine_->getBindingDimensions(ibinding)).c_str(), + data_type_string(engine_->getBindingDataType(ibinding)) + ); + } + } +}; + +std::shared_ptr load(const std::string& file){ + + std::shared_ptr impl(new EngineImpl()); + if(!impl->load(file)) impl.reset(); + return impl; +} + +}; // namespace TensorRT \ No newline at end of file diff --git a/trlo/src/centerpp_node/centerpp_node.cpp b/trlo/src/centerpp_node/centerpp_node.cpp new file mode 100644 index 0000000..dfe2fec --- /dev/null +++ b/trlo/src/centerpp_node/centerpp_node.cpp @@ -0,0 +1,1015 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +// PCL specific includes +#include +#include +#include +#include +#include +#include +#include +#include "pcl_ros/impl/transforms.hpp" + +#include +#include "center_pointpillars/centerpoint.h" + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "3d_mot/imm_ukf_jpda.h" + +#include + +#define GPU_CHECK(ans) \ + { GPUAssert((ans), __FILE__, __LINE__); } +inline void GPUAssert(cudaError_t code, const char *file, int line, + bool abort = true) { + if (code != cudaSuccess) { + fprintf(stderr, "GPUassert: %s %s %d\n", cudaGetErrorString(code), file, + line); + if (abort) + exit(code); + } +}; + +std::vector color; + +std::vector avg_centerpoint_time; +std::vector avg_ukf_time; + + +void GetDeviceInfo() +{ + cudaDeviceProp prop; + + int count = 0; + cudaGetDeviceCount(&count); + printf("\nGPU has cuda devices: %d\n", count); + for (int i = 0; i < count; ++i) { + cudaGetDeviceProperties(&prop, i); + printf("----device id: %d info----\n", i); + printf(" GPU : %s \n", prop.name); + printf(" Capbility: %d.%d\n", prop.major, prop.minor); + printf(" Global memory: %luMB\n", prop.totalGlobalMem >> 20); + printf(" Const memory: %luKB\n", prop.totalConstMem >> 10); + printf(" SM in a block: %luKB\n", prop.sharedMemPerBlock >> 10); + printf(" warp size: %d\n", prop.warpSize); + printf(" threads in a block: %d\n", prop.maxThreadsPerBlock); + printf(" block dim: (%d,%d,%d)\n", prop.maxThreadsDim[0], prop.maxThreadsDim[1], prop.maxThreadsDim[2]); + printf(" grid dim: (%d,%d,%d)\n", prop.maxGridSize[0], prop.maxGridSize[1], prop.maxGridSize[2]); + } + printf("\n"); +} + +void initDevice(int devNum) { + int dev = devNum; + cudaDeviceProp deviceProp; + + GPU_CHECK(cudaGetDeviceProperties(&deviceProp, dev)); + printf("Using device %d: %s\n", dev, deviceProp.name); + GPU_CHECK(cudaSetDevice(dev)); +} + +void SaveToBin(const pcl::PointCloud& cloud, const std::string& path) { + // std::cout << "bin_path: " << path << std::endl; + //Create & write .bin file + std::ofstream out; + out.open(path, std::ios::out|std::ios::binary); + if(!out.good()) { + std::cout<<"Couldn't open "< targetPoints; + std::vector> targetVandYaw; + std::vector trackManage; + std::vector isStaticVec; + std::vector isVisVec; + std::vector> visBBs; + + Center_PointPillars_ROS(ros::NodeHandle nh); + ~Center_PointPillars_ROS(); + + void Process(); + void extractBBoxPointcloud(std::vector filter_BBox, pcl::PointCloud::Ptr cloud_in, pcl::PointCloud::Ptr& cloud_out, pcl::PointCloud::Ptr& cloud_cluster); + void mot_3d(std_msgs::Header in_msg_header, std::vector filter_BBox, std::vector& dynamic_BBox); + + private: + ros::NodeHandle nh_; + ros::Subscriber sub_pointcloud_; + ros::Subscriber sub_odom_; + ros::Publisher pub_pointcloud_static_; + ros::Publisher pub_pointcloud_raw_; + ros::Publisher pub_bbox_; + ros::Publisher pub_dynamic_bbox_; + ros::Publisher pub_pointcloud_cluster_; + ros::Publisher pub_text_vel_; + ros::Publisher pub_tracking_center_; + ros::Publisher pub_arrows_; + ros::Publisher pub_box_markers_; + ros::Publisher pub_center_points_; + + cudaEvent_t start_, stop_; + cudaStream_t stream_ = NULL; + + Params params; + + std::string Model_File_Dir_; + std::string saveBinFile_; + + std::string odom_frame_; + std::string child_frame_; + + pcl::PointCloud::Ptr original_scan_; + + double MINIMUM_RANGE; + double MAXMUM_RANGE; + bool crop_use_; + double crop_size_; + + bool vf_use_; + double vf_res_; + + pcl::CropBox crop; + pcl::VoxelGrid vf; + std::deque odom_queue; + visualization_msgs::MarkerArray center_points_array; + + bool verbose = true; + + std::unique_ptr center_pointpillars_ptr_; + nanoflann::KdTreeFLANN::Ptr objects_kdtree_; + + void PointCloud_Callback(const sensor_msgs::PointCloud2Ptr &msg); + void Odometry_Callback(const nav_msgs::OdometryPtr &odom); + void publishCloud(std_msgs::Header header, const pcl::PointCloud::Ptr in_cloud_to_publish_ptr); + void publishObjectBoundingBox(std_msgs::Header in_msg_header, std::vector filter_BBox); + void publishDynamicBoundingBox(std_msgs::Header in_msg_header, std::vector dynamic_BBox); + void publishClusterCloud(std_msgs::Header header, const pcl::PointCloud::Ptr cloud_in, std::vector cluster_indices); + void publishVelArrows(pcl::PointCloud egoTFPoints, ros::Time input_time); + void publishTrackingCenter(pcl::PointCloud egoTFPoints, ros::Time input_time); + void publishBoundingBoxMarkers(ros::Time input_time); + + void preprocessPoints(const pcl::PointCloud::Ptr &cloud_in, float th1, float th2); + void removeClosedPointCloud(const pcl::PointCloud &cloud_in, pcl::PointCloud &cloud_out, float th1, float th2); +}; + +Center_PointPillars_ROS::Center_PointPillars_ROS(ros::NodeHandle nh) : nh_(nh) { + ros::param::param("Model_File_Dir", this->Model_File_Dir_, "/home/jyp/3D_LiDAR_SLAM/trlo_ws/src/trlo/model/center_pointpillars/"); + ros::param::param("SavaData_File", this->saveBinFile_, "/home/jyp/3D_LiDAR_SLAM/trlo_ws/src/trlo/data/data.bin"); + ros::param::param("~center_pp/frame/odom_frame", this->odom_frame_, "robot/odom"); + ros::param::param("~center_pp/frame/child_frame", this->child_frame_, "robot/base_link"); + + ros::param::param("~center_pp/preprocessing/threshold/MINIMUM_RANGE", this->MINIMUM_RANGE, 0.5); + ros::param::param("~center_pp/preprocessing/threshold/MAXMUM_RANGE", this->MAXMUM_RANGE, 80); + + // Crop Box Filter + ros::param::param("~center_pp/preprocessing/cropBoxFilter/use", this->crop_use_, false); + ros::param::param("~center_pp/preprocessing/cropBoxFilter/size", this->crop_size_, 1.0); + + // Voxel Grid Filter + ros::param::param("~center_pp/preprocessing/voxelFilter/use", this->vf_use_, true); + ros::param::param("~center_pp/preprocessing/voxelFilter/res", this->vf_res_, 0.05); + + checkCudaErrors(cudaEventCreate(&this->start_)); + checkCudaErrors(cudaEventCreate(&this->stop_)); + GPU_CHECK(cudaStreamCreate(&this->stream_)); + this->center_pointpillars_ptr_.reset(new CenterPoint(this->Model_File_Dir_, this->verbose)); // 外部定义调用不了cuda函数 + this->objects_kdtree_.reset(new nanoflann::KdTreeFLANN()); + this->original_scan_.reset(new pcl::PointCloud()); + this->crop.setNegative(true); + this->crop.setMin(Eigen::Vector4f(-this->crop_size_, -this->crop_size_, -this->crop_size_, 1.0)); + this->crop.setMax(Eigen::Vector4f(this->crop_size_, this->crop_size_, this->crop_size_, 1.0)); + + this->vf.setLeafSize(this->vf_res_, this->vf_res_, this->vf_res_); + center_pointpillars_ptr_->prepare(); + setlocale(LC_ALL,""); +} + + +Center_PointPillars_ROS::~Center_PointPillars_ROS(){ + checkCudaErrors(cudaEventDestroy(this->start_)); + checkCudaErrors(cudaEventDestroy(this->stop_)); + checkCudaErrors(cudaStreamDestroy(this->stream_)); +} + + +void Center_PointPillars_ROS::Process() { + std::cout << "Ready to receive point cloud topic!" << std::endl; + this->sub_pointcloud_ = nh_.subscribe("pointcloud", 1, &Center_PointPillars_ROS::PointCloud_Callback, this); + this->sub_odom_ = nh_.subscribe ("odom", 160, &Center_PointPillars_ROS::Odometry_Callback, this); + this->pub_pointcloud_static_ = nh_.advertise("pointcloud_static", 10); + this->pub_pointcloud_raw_ = nh_.advertise("pointcloud_raw", 10); + this->pub_bbox_ = nh_.advertise("box", 10, true); + this->pub_dynamic_bbox_ = nh_.advertise("dynamic_box", 10, true); + this->pub_pointcloud_cluster_ = nh_.advertise("pointcloud_cluster", 10); + this->pub_text_vel_ = nh_.advertise("centerpoint_vel", 10); + this->pub_tracking_center_ = nh_.advertise("tracking_center", 10); + this->pub_arrows_ = nh_.advertise("object_vel_arrows", 10); + this->pub_box_markers_ = nh_.advertise ("box_markers", 10); + this->pub_center_points_ = nh_.advertise ("center_markers", 10); + ros::spin(); +} + + + +void Center_PointPillars_ROS::PointCloud_Callback(const sensor_msgs::PointCloud2Ptr &msg) { + + pcl::PointCloud::Ptr in_cloud_ptr(new pcl::PointCloud()); + pcl::fromROSMsg(*msg, *in_cloud_ptr); + + // std::cout << "process before size is : " << in_cloud_ptr->size() << std::endl; + // this->preprocessPoints(in_cloud_ptr, this->MINIMUM_RANGE, this->MAXMUM_RANGE); + // std::cout << "process after size is : " << in_cloud_ptr->size() << std::endl; + + SaveToBin(*in_cloud_ptr, this->saveBinFile_); + // std::cout << "load file: "<< this->saveBinFile_ <saveBinFile_.c_str() , &pc_data, &length); + size_t points_num = length / (5 * sizeof(float)) ; + + float *d_points = nullptr; + checkCudaErrors(cudaMallocManaged((void **)&d_points, MAX_POINTS_NUM * 5 * sizeof(float))); + checkCudaErrors(cudaMemcpy(d_points, pc_data, length, cudaMemcpyHostToDevice)); + checkCudaErrors(cudaDeviceSynchronize()); + + cudaEventRecord(this->start_, this->stream_); + + double t1 = ros::Time::now().toSec(); + center_pointpillars_ptr_->doinfer((void *)d_points, points_num, this->stream_); + double t2 = ros::Time::now().toSec(); + avg_centerpoint_time.push_back((t2 - t1) * 1000); + + float elapsedTime = 0.0f; + + cudaEventRecord(this->stop_, this->stream_); + cudaEventSynchronize(this->stop_); + // cudaEventElapsedTime(&elapsedTime, this->start_, this->stop_); + + checkCudaErrors(cudaFree(d_points)); + + + std::vector filter_BBox, dynamic_BBox; + for (auto box : this->center_pointpillars_ptr_->nms_pred_) { + // car(id=0)/pedestrain(id=8)/cyclists(id=6)/truck(id=3) + // if ((box.id == 0 && box.score > 0.3) || (box.id == 6 && box.score > 0.5) || (box.id == 8 && box.score > 0.2)) { + // filter_BBox.push_back(box); + // } + // if (((box.id == 0 && box.score > 0.5) || (box.id == 6 && box.score > 0.75)) && abs(box.vy) > 0.001) { + // dynamic_BBox.push_back(box); + // } + if ((box.id == 0 && box.score > 0.5) || (box.id == 6 && box.score > 0.75)) { + filter_BBox.push_back(box); + } + } + + this->mot_3d(msg->header, filter_BBox, dynamic_BBox); + + // std::cout << "filter box size: " << filter_BBox.size() << std::endl; + // std::cout << "dynamic box size: " << dynamic_BBox.size() << std::endl; + + if (filter_BBox.empty()) { + this->preprocessPoints(in_cloud_ptr, this->MINIMUM_RANGE, this->MAXMUM_RANGE); + this->publishCloud(msg->header, in_cloud_ptr); + return; + } + + pcl::PointCloud::Ptr out_cloud_ptr(new pcl::PointCloud()); + pcl::PointCloud::Ptr cloud_cluster(new pcl::PointCloud()); + this->extractBBoxPointcloud(dynamic_BBox, in_cloud_ptr, out_cloud_ptr, cloud_cluster); + + double avg_centerpoint_totaltime = std::accumulate(avg_centerpoint_time.begin(), avg_centerpoint_time.end(), 0.0) / avg_centerpoint_time.size(); + double avg_ukf_totaltime = std::accumulate(avg_ukf_time.begin(), avg_ukf_time.end(), 0.0) / avg_ukf_time.size(); + std::cout << "CenterPoint Time :: " << std::setfill(' ') << std::setw(6) << avg_centerpoint_time.back() << " ms // Avg: " << std::setw(5) << avg_centerpoint_totaltime << std::endl; + std::cout << "UKF Time :: " << std::setfill(' ') << std::setw(6) << avg_ukf_time.back() << " ms // Avg: " << std::setw(5) << avg_ukf_totaltime << std::endl; + + + + this->preprocessPoints(out_cloud_ptr, this->MINIMUM_RANGE, this->MAXMUM_RANGE); + + this->publishCloud(msg->header, out_cloud_ptr); + this->publishObjectBoundingBox(msg->header, filter_BBox); + this->publishDynamicBoundingBox(msg->header, dynamic_BBox); + // this->publishClusterCloud(msg->header, cloud_cluster, cluster_indices); + +} + + +void Center_PointPillars_ROS::Odometry_Callback(const nav_msgs::OdometryPtr &odom) { + this->odom_queue.push_back(*odom); +} + + + +void Center_PointPillars_ROS::extractBBoxPointcloud(std::vector filter_BBox, pcl::PointCloud::Ptr cloud_in, pcl::PointCloud::Ptr& cloud_out, pcl::PointCloud::Ptr& cloud_cluster) { + // KDtree:O((logm)^2) + O(m^(1-1/3)+1) * n + // Violent methods:O(m*n) + if (filter_BBox.empty()) { + *cloud_out = *cloud_in; + return; + } + + pcl::PointCloud::Ptr objects_cloud; + objects_cloud.reset(new pcl::PointCloud()); + for (const auto box : filter_BBox) { + pcl::PointXYZ p; + p.x = box.x; + p.y = box.y; + p.z = box.z; + objects_cloud->points.push_back(p); + } + this->objects_kdtree_->setInputCloud(objects_cloud); + + int cloudSize = cloud_in->size(); + for (size_t i = 0; i < cloudSize; i++) + { + pcl::PointXYZ p; + p.x = cloud_in->points[i].x; + p.y = cloud_in->points[i].y; + p.z = cloud_in->points[i].z; + + std::vector k_indices(1); + std::vector k_sqr_distances(1); + this->objects_kdtree_->nearestKSearch(p, 1, k_indices, k_sqr_distances); + Bndbox nearest_object = filter_BBox[k_indices[0]]; + + if (k_sqr_distances[k_indices[0]] > 2.0) { + cloud_out->points.push_back(cloud_in->points[i]); + continue; + } + if ((p.x < nearest_object.x - nearest_object.l / 2 || p.x > nearest_object.x + nearest_object.l / 2) || + (p.y < nearest_object.y - nearest_object.w / 2 || p.y > nearest_object.y + nearest_object.w / 2) || + (p.z < nearest_object.z - nearest_object.h / 2 || p.z > nearest_object.z + nearest_object.h / 2)) { + cloud_out->points.push_back(cloud_in->points[i]); + continue; + } + cloud_cluster->points.push_back(p); + } + // std::cout << "cluster size is: " << cloud_cluster->size() << std::endl; +} + + +void Center_PointPillars_ROS::publishCloud(std_msgs::Header header, const pcl::PointCloud::Ptr in_cloud_to_publish_ptr) { + sensor_msgs::PointCloud2 cloud_msg; + pcl::toROSMsg(*in_cloud_to_publish_ptr, cloud_msg); + cloud_msg.header = header; + cloud_msg.header.frame_id = this->child_frame_; + this->pub_pointcloud_static_.publish(cloud_msg); +} + + +void Center_PointPillars_ROS::publishObjectBoundingBox(std_msgs::Header in_msg_header, std::vector filter_BBox) { + + jsk_recognition_msgs::BoundingBoxArray arr_bbox; + int i = 0; + + for (const auto box : filter_BBox) { + jsk_recognition_msgs::BoundingBox bbox; + + bbox.header = in_msg_header; + bbox.header.frame_id = this->child_frame_; + bbox.pose.position.x = box.x; + bbox.pose.position.y = box.y; + bbox.pose.position.z = box.z; + bbox.dimensions.x = box.w; // width + bbox.dimensions.y = box.l; // length + bbox.dimensions.z = box.h; // height + // Using tf::Quaternion for quaternion from roll, pitch, yaw + tf::Quaternion q = tf::createQuaternionFromRPY(0, 0, -box.rt); + bbox.pose.orientation.x = q.x(); + bbox.pose.orientation.y = q.y(); + bbox.pose.orientation.z = q.z(); + bbox.pose.orientation.w = q.w(); + bbox.value = box.score; + bbox.label = box.id; + arr_bbox.boxes.push_back(bbox); + // if(box.score>0.5){ + // arr_bbox.boxes.push_back(bbox); + // } + + } + // std::cout<<"find bbox Num:"<child_frame_; + + this->pub_bbox_.publish(arr_bbox); +} + + +void Center_PointPillars_ROS::publishDynamicBoundingBox(std_msgs::Header in_msg_header, std::vector dynamic_BBox) { + + jsk_recognition_msgs::BoundingBoxArray arr_bbox; + visualization_msgs::MarkerArray text_vel_array; + visualization_msgs::Marker text_vel, center_points; + static int i = 0; + center_points.lifetime = ros::Duration(); + center_points.header = in_msg_header; + center_points.header.frame_id = this->child_frame_; + center_points.ns = "center_points"; + center_points.action = visualization_msgs::Marker::ADD; + center_points.type = visualization_msgs::Marker::POINTS; + center_points.scale.x = 0.7; + center_points.scale.y = 0.7; + center_points.scale.z = 0.7; + + for (const auto box : dynamic_BBox) { + jsk_recognition_msgs::BoundingBox bbox; + + bbox.header = in_msg_header; + bbox.header.frame_id = this->child_frame_; // Replace with your frame_id + bbox.pose.position.x = box.x; + bbox.pose.position.y = box.y; + bbox.pose.position.z = box.z; + bbox.dimensions.x = box.w; // width + bbox.dimensions.y = box.l; // length + bbox.dimensions.z = box.h; // height + // Using tf::Quaternion for quaternion from roll, pitch, yaw + tf::Quaternion q = tf::createQuaternionFromRPY(0, 0, -box.rt); + bbox.pose.orientation.x = q.x(); + bbox.pose.orientation.y = q.y(); + bbox.pose.orientation.z = q.z(); + bbox.pose.orientation.w = q.w(); + bbox.value = box.score; + bbox.label = box.id; + arr_bbox.boxes.push_back(bbox); + // if(box.score>0.5){ + // arr_bbox.boxes.push_back(bbox); + // } + + text_vel.header = in_msg_header; + text_vel.header.frame_id = this->child_frame_; + text_vel.ns = "dynamic_vel"; + text_vel.action = visualization_msgs::Marker::ADD; + text_vel.id = i++; + text_vel.type = visualization_msgs::Marker::TEXT_VIEW_FACING; + text_vel.scale.z = 1; + text_vel.color.r = text_vel.color.b = text_vel.color.g = 1; + text_vel.color.a = 1; + float vel = box.vy; + std::ostringstream oss; + oss << std::setprecision(2) << vel; + text_vel.text = oss.str() + "m/s"; + text_vel.pose.orientation.x = q.x(); + text_vel.pose.orientation.y = q.y(); + text_vel.pose.orientation.z = q.z(); + text_vel.pose.orientation.w = q.w(); + text_vel.pose.position.x = box.x; + text_vel.pose.position.y = box.y; + text_vel.pose.position.z = box.z + box.h / 2 + 0.1; + text_vel_array.markers.push_back(text_vel); + + center_points.id = i; + center_points.type = visualization_msgs::Marker::POINTS; + center_points.color.r = color[int(3) * i]; + center_points.color.b = color[int(3) * i + 1]; + center_points.color.g = color[int(3) * i + 2]; + center_points.color.a = 0.7; + center_points.pose.orientation.w = 1; + geometry_msgs::Point p; + p.x = box.x; + p.y = box.y; + p.z = box.z; + center_points.points.push_back(p); + + this->center_points_array.markers.push_back(center_points); + + } + // std::cout<<"find bbox Num:"<child_frame_; + + this->pub_dynamic_bbox_.publish(arr_bbox); + this->pub_text_vel_.publish(text_vel_array); + this->pub_center_points_.publish(this->center_points_array); +} + + + +void Center_PointPillars_ROS::publishClusterCloud(std_msgs::Header header, const pcl::PointCloud::Ptr cloud_in, std::vector cluster_indices) { + int color_index = 0; + pcl::PointCloud::Ptr color_point(new pcl::PointCloud()); + int clusterSize = cluster_indices.size(); + for (int i = 0; i < clusterSize; i++) { + int clusterindixSize = cluster_indices[i].indices.size(); + for (int j = 0; j < clusterindixSize; j++) { + pcl::PointXYZRGB point; + point.x = cloud_in->points[cluster_indices[i].indices[j]].x; + point.y = cloud_in->points[cluster_indices[i].indices[j]].y; + point.z = cloud_in->points[cluster_indices[i].indices[j]].z; + point.r = color[int(3) * color_index]; + point.g = color[int(3) * color_index + 1]; + point.b = color[int(3) * color_index + 2]; + color_point->push_back(point); + } + color_index++; + } + + sensor_msgs::PointCloud2 cloud_msg; + pcl::toROSMsg(*color_point, cloud_msg); + cloud_msg.header = header; + cloud_msg.header.frame_id = this->child_frame_; + this->pub_pointcloud_cluster_.publish(cloud_msg); +} + + +void Center_PointPillars_ROS::publishVelArrows(pcl::PointCloud egoTFPoints, ros::Time input_time) { + + int targetSize = this->targetPoints.size(); + for(int i = 0; i < targetSize; i++){ + visualization_msgs::Marker arrowsG; + arrowsG.lifetime = ros::Duration(0.1); + if(this->trackManage[i] == 0 ) { + continue; + } + if(this->isVisVec[i] == false ) { + continue; + } + if(this->isStaticVec[i] == true){ + continue; + } + arrowsG.header.frame_id = this->child_frame_; + + arrowsG.header.stamp= input_time; + arrowsG.ns = "arrows"; + arrowsG.action = visualization_msgs::Marker::ADD; + arrowsG.type = visualization_msgs::Marker::ARROW; + // green + arrowsG.color.g = 1.0f; + // arrowsG.color.r = 1.0f; + arrowsG.color.a = 1.0; + arrowsG.id = i; + geometry_msgs::Point p; + // assert(targetPoints[i].size()==4); + p.x = egoTFPoints[i].x; + p.y = egoTFPoints[i].y; + p.z = -1.73/2; + double tv = this->targetVandYaw[i][0]; + double tyaw = this->targetVandYaw[i][1]; + + // Set the pose of the marker. This is a full 6DOF pose relative to the frame/time specified in the header + arrowsG.pose.position.x = p.x; + arrowsG.pose.position.y = p.y; + arrowsG.pose.position.z = p.z; + + // convert from 3 angles to quartenion + tf::Matrix3x3 obs_mat; + obs_mat.setEulerYPR(tyaw, 0, 0); // yaw, pitch, roll + tf::Quaternion q_tf; + obs_mat.getRotation(q_tf); + arrowsG.pose.orientation.x = q_tf.getX(); + arrowsG.pose.orientation.y = q_tf.getY(); + arrowsG.pose.orientation.z = q_tf.getZ(); + arrowsG.pose.orientation.w = q_tf.getW(); + + // Set the scale of the arrowsG -- 1x1x1 here means 1m on a side + arrowsG.scale.x = tv; + arrowsG.scale.y = 0.1; + arrowsG.scale.z = 0.1; + + this->pub_arrows_.publish(arrowsG); + } + +} + + +void Center_PointPillars_ROS::publishTrackingCenter(pcl::PointCloud egoTFPoints, ros::Time input_time) { + + visualization_msgs::Marker pointsY, pointsG, pointsR, pointsB; + pointsY.header.frame_id = pointsG.header.frame_id = pointsR.header.frame_id = pointsB.header.frame_id = this->child_frame_; + + pointsY.header.stamp= pointsG.header.stamp= pointsR.header.stamp =pointsB.header.stamp = input_time; + pointsY.ns= pointsG.ns = pointsR.ns =pointsB.ns= "points"; + pointsY.action = pointsG.action = pointsR.action = pointsB.action = visualization_msgs::Marker::ADD; + pointsY.pose.orientation.w = pointsG.pose.orientation.w = pointsR.pose.orientation.w =pointsB.pose.orientation.w= 1.0; + + pointsY.id = 1; + pointsG.id = 2; + pointsR.id = 3; + pointsB.id = 4; + pointsY.type = pointsG.type = pointsR.type = pointsB.type = visualization_msgs::Marker::POINTS; + + // POINTS markers use x and y scale for width/height respectively + pointsY.scale.x =pointsG.scale.x =pointsR.scale.x = pointsB.scale.x=0.5; + pointsY.scale.y =pointsG.scale.y =pointsR.scale.y = pointsB.scale.y = 0.5; + + // yellow + pointsY.color.r = 1.0f; + pointsY.color.g = 1.0f; + pointsY.color.b = 0.0f; + pointsY.color.a = 1.0; + + // green + pointsG.color.g = 1.0f; + pointsG.color.a = 1.0; + + // red + pointsR.color.r = 1.0; + pointsR.color.a = 1.0; + + // blue + pointsB.color.b = 1.0; + pointsB.color.a = 1.0; + + int targetSize = this->targetPoints.size(); + for(int i = 0; i < targetSize; i++){ + if(this->trackManage[i] == 0) continue; + geometry_msgs::Point p; + // p.x = this->targetPoints[i].x; + // p.y = this->targetPoints[i].y; + p.x = egoTFPoints[i].x; + p.y = egoTFPoints[i].y; + p.z = -1.73/2; + + if(this->isStaticVec[i] == true){ + pointsB.points.push_back(p); + } + else if(this->trackManage[i] < 5 ){ + pointsY.points.push_back(p); + } + else if(this->trackManage[i] == 5){ + pointsG.points.push_back(p); + } + else if(this->trackManage[i] > 5){ + pointsR.points.push_back(p); + } + } + this->pub_tracking_center_.publish(pointsY); + this->pub_tracking_center_.publish(pointsG); + this->pub_tracking_center_.publish(pointsR); + this->pub_tracking_center_.publish(pointsB); +} + + +void Center_PointPillars_ROS::publishBoundingBoxMarkers(ros::Time input_time) { + + visualization_msgs::Marker line_list; + line_list.header.frame_id = this->child_frame_; + + line_list.header.stamp = input_time; + line_list.ns = "boxes"; + line_list.action = visualization_msgs::Marker::ADD; + line_list.pose.orientation.w = 1.0; + + line_list.id = 0; + line_list.type = visualization_msgs::Marker::LINE_LIST; + + //LINE_LIST markers use only the x component of scale, for the line width + line_list.scale.x = 0.1; + // Points are green + line_list.color.g = 1.0f; + line_list.color.a = 1.0; + + int id = 0;std::string ids; + int targetSize = this->visBBs.size(); + for(int objectI = 0; objectI < targetSize; objectI ++){ + for(int pointI = 0; pointI < 4; pointI++){ + assert((pointI+1)%4 < this->visBBs[objectI].size()); + assert((pointI+4) < this->visBBs[objectI].size()); + assert((pointI+1)%4+4 < this->visBBs[objectI].size()); + id ++; ids = to_string(id); + geometry_msgs::Point p; + p.x = this->visBBs[objectI][pointI].x; + p.y = this->visBBs[objectI][pointI].y; + p.z = this->visBBs[objectI][pointI].z; + line_list.points.push_back(p); + p.x = this->visBBs[objectI][(pointI+1)%4].x; + p.y = this->visBBs[objectI][(pointI+1)%4].y; + p.z = this->visBBs[objectI][(pointI+1)%4].z; + line_list.points.push_back(p); + + p.x = this->visBBs[objectI][pointI].x; + p.y = this->visBBs[objectI][pointI].y; + p.z = this->visBBs[objectI][pointI].z; + line_list.points.push_back(p); + p.x = this->visBBs[objectI][pointI+4].x; + p.y = this->visBBs[objectI][pointI+4].y; + p.z = this->visBBs[objectI][pointI+4].z; + line_list.points.push_back(p); + + p.x = this->visBBs[objectI][pointI+4].x; + p.y = this->visBBs[objectI][pointI+4].y; + p.z = this->visBBs[objectI][pointI+4].z; + line_list.points.push_back(p); + p.x = this->visBBs[objectI][(pointI+1)%4+4].x; + p.y = this->visBBs[objectI][(pointI+1)%4+4].y; + p.z = this->visBBs[objectI][(pointI+1)%4+4].z; + line_list.points.push_back(p); + } + } + this->pub_box_markers_.publish(line_list); +} + + +void Center_PointPillars_ROS::preprocessPoints(const pcl::PointCloud::Ptr &cloud_in, float th1, float th2) { + + // Original Scan + *this->original_scan_ = *cloud_in; + sensor_msgs::PointCloud2 cloud_msg; + pcl::toROSMsg(*this->original_scan_, cloud_msg); + // cloud_msg.header.stamp = cloud_in->header.stamp; + cloud_msg.header.frame_id = this->child_frame_; + this->pub_pointcloud_raw_.publish(cloud_msg); + + // Remove NaNs + std::vector idx; + cloud_in->is_dense = false; + pcl::removeNaNFromPointCloud(*cloud_in, *cloud_in, idx); + this->removeClosedPointCloud(*cloud_in, *cloud_in, th1, th2); + + // Crop Box Filter + if (this->crop_use_) { + this->crop.setInputCloud(cloud_in); + this->crop.filter(*cloud_in); + } + + // Voxel Grid Filter + if (this->vf_use_) { + this->vf.setInputCloud(cloud_in); + this->vf.filter(*cloud_in); + } + +} + +void Center_PointPillars_ROS::removeClosedPointCloud(const pcl::PointCloud &cloud_in, pcl::PointCloud &cloud_out, float th1, float th2) +{ + if (&cloud_in != &cloud_out) + { + cloud_out.header = cloud_in.header; + cloud_out.points.resize(cloud_in.points.size()); + } + + size_t j = 0; + + for (size_t i = 0; i < cloud_in.points.size(); ++i) + { + float dis = cloud_in.points[i].x * cloud_in.points[i].x + cloud_in.points[i].y * cloud_in.points[i].y + cloud_in.points[i].z * cloud_in.points[i].z; + if (dis < th1 * th1) + continue; + if (dis > th2 * th2) + continue; + cloud_out.points[j++] = cloud_in.points[i]; + } + + if (j != cloud_in.points.size()) + { + cloud_out.points.resize(j); + } + + cloud_out.height = 1; + cloud_out.width = static_cast(j); + cloud_out.is_dense = true; +} + + +void Center_PointPillars_ROS::mot_3d(std_msgs::Header in_msg_header, std::vector filter_BBox, std::vector& dynamic_BBox) +{ + double timestamp = in_msg_header.stamp.toSec(); + ros::Time input_time = in_msg_header.stamp; + + int box_num = filter_BBox.size(); + // convert local to global------------------------- + std::vector> bBoxes; + pcl::PointCloud oneBbox; + + for(int i = 0; i < box_num; i++) + { + pcl::PointXYZ o; + o.x = filter_BBox[i].x - filter_BBox[i].l / 2; + o.y = filter_BBox[i].y - filter_BBox[i].w / 2; + o.z = filter_BBox[i].z - filter_BBox[i].h / 2; + oneBbox.push_back(o); + o.x = filter_BBox[i].x + filter_BBox[i].l / 2; + o.y = filter_BBox[i].y - filter_BBox[i].w / 2; + o.z = filter_BBox[i].z - filter_BBox[i].h / 2; + oneBbox.push_back(o); + o.x = filter_BBox[i].x + filter_BBox[i].l / 2; + o.y = filter_BBox[i].y + filter_BBox[i].w / 2; + o.z = filter_BBox[i].z - filter_BBox[i].h / 2; + oneBbox.push_back(o); + o.x = filter_BBox[i].x - filter_BBox[i].l / 2; + o.y = filter_BBox[i].y + filter_BBox[i].w / 2; + o.z = filter_BBox[i].z - filter_BBox[i].h / 2; + oneBbox.push_back(o); + o.x = filter_BBox[i].x - filter_BBox[i].l / 2; + o.y = filter_BBox[i].y - filter_BBox[i].w / 2; + o.z = filter_BBox[i].z + filter_BBox[i].h / 2; + oneBbox.push_back(o); + o.x = filter_BBox[i].x + filter_BBox[i].l / 2; + o.y = filter_BBox[i].y - filter_BBox[i].w / 2; + o.z = filter_BBox[i].z + filter_BBox[i].h / 2; + oneBbox.push_back(o); + o.x = filter_BBox[i].x + filter_BBox[i].l / 2; + o.y = filter_BBox[i].y + filter_BBox[i].w / 2; + o.z = filter_BBox[i].z + filter_BBox[i].h / 2; + oneBbox.push_back(o); + o.x = filter_BBox[i].x - filter_BBox[i].l / 2; + o.y = filter_BBox[i].y + filter_BBox[i].w / 2; + o.z = filter_BBox[i].z + filter_BBox[i].h / 2; + + bBoxes.push_back(oneBbox); + oneBbox.clear(); + } + + + + Eigen::Matrix4f last_T; + + if (this->odom_queue.empty()) + { + last_T.setIdentity(); + } + else + { + Eigen::Quaternionf last_q(this->odom_queue.front().pose.pose.orientation.w, this->odom_queue.front().pose.pose.orientation.x, this->odom_queue.front().pose.pose.orientation.y, this->odom_queue.front().pose.pose.orientation.z); + last_T.block<3,3>(0,0) = last_q.toRotationMatrix(); + Eigen::Vector3f last_t(this->odom_queue.front().pose.pose.position.x, this->odom_queue.front().pose.pose.position.y, this->odom_queue.front().pose.pose.position.z); + last_T.block<3,1>(0,3) = last_t; + } + // getOriginPoints(last_T.block<3,3>(0,0)); + + pcl::PointCloud newBox; + for(int i = 0; i < box_num; i++ ){ + bBoxes[i].header.frame_id = this->odom_frame_; + + pcl::transformPointCloud(bBoxes[i], newBox, last_T); + bBoxes[i] = newBox; + bBoxes[i].header.frame_id = this->odom_frame_; + } + //end converting---------------------------------------- + this->targetPoints.clear(); + this->targetVandYaw.clear(); + this->trackManage.clear(); + this->isStaticVec.clear(); + this->isVisVec.clear(); + this->visBBs.clear(); + double t1 = ros::Time::now().toSec(); + immUkfJpdaf(bBoxes, timestamp, this->targetPoints, this->targetVandYaw, this->trackManage, this->isStaticVec, this->isVisVec, this->visBBs); + double t2 = ros::Time::now().toSec(); + avg_ukf_time.push_back((t2 - t1) * 1000); + // ROS_INFO("UKF cost time:%f ms", (t2 - t1) * 1000); + + assert(targetPoints.size() == trackManage.size()); + assert(targetPoints.size()== targetVandYaw.size()); + + //start converting to ego tf------------------------- + if (this->odom_queue.empty()) + { + last_T.setIdentity(); + } + else + { + Eigen::Quaternionf last_q(this->odom_queue.front().pose.pose.orientation.w, this->odom_queue.front().pose.pose.orientation.x, this->odom_queue.front().pose.pose.orientation.y, this->odom_queue.front().pose.pose.orientation.z); + last_T.block<3,3>(0,0) = last_q.toRotationMatrix().inverse(); + Eigen::Vector3f last_t(this->odom_queue.front().pose.pose.position.x, this->odom_queue.front().pose.pose.position.y, this->odom_queue.front().pose.pose.position.z); + last_t = -last_T.block<3,3>(0,0) * last_t; + last_T.block<3,1>(0,3) = last_t; + } + + // converting from global to ego tf for visualization + // processing targetPoints + pcl::PointCloud egoTFPoints; + this->targetPoints.header.frame_id = this->child_frame_; + pcl::transformPointCloud(targetPoints, egoTFPoints, last_T); + + //processing visBBs + pcl::PointCloud visEgoBB; + for(int i = 0; i < visBBs.size(); i++){ + this->visBBs[i].header.frame_id = this->child_frame_; + pcl::transformPointCloud(this->visBBs[i], visEgoBB, last_T); + this->visBBs[i] = visEgoBB; + } + //end converting to ego tf--------------------------- + + pcl::PointCloud::Ptr objects_cloud; + objects_cloud.reset(new pcl::PointCloud()); + for (const auto box : filter_BBox) { + pcl::PointXYZ p; + p.x = box.x; + p.y = box.y; + p.z = 0; + objects_cloud->points.push_back(p); + } + this->objects_kdtree_->setInputCloud(objects_cloud); + + int targetSize = targetPoints.size(); + for (int i = 0; i < targetSize; i++) + { + if(this->trackManage[i] == 0 ) { + continue; + } + if(this->isVisVec[i] == false ) { + continue; + } + if(this->isStaticVec[i] == true){ + continue; + } + pcl::PointXYZ p; + p.x = egoTFPoints[i].x; + p.y = egoTFPoints[i].y; + p.z = 0; + + std::vector k_indices(1); + std::vector k_sqr_distances(1); + this->objects_kdtree_->nearestKSearch(p, 1, k_indices, k_sqr_distances); + Bndbox nearest_object = filter_BBox[k_indices[0]]; + dynamic_BBox.push_back(nearest_object); + } + + if (!this->odom_queue.empty()) + this->odom_queue.pop_front(); + + // this->publishVelArrows(egoTFPoints, input_time); + // this->publishTrackingCenter(egoTFPoints, input_time); + // this->publishBoundingBoxMarkers(input_time); +} + + + + +} + + + + +int main(int argc, char **argv) { + ros::init(argc, argv, "centerpp_node"); + ros::NodeHandle nh("~"); + + color.clear(); + for (size_t i_segment = 0; i_segment < 100; i_segment++) + { + color.push_back(static_cast(rand() % 256)); + color.push_back(static_cast(rand() % 256)); + color.push_back(static_cast(rand() % 256)); + } + + // GetDeviceInfo(); + initDevice(0); + + cpp::Center_PointPillars_ROS center_pintPillars_ros(nh); + center_pintPillars_ros.Process(); + + return 0; +} diff --git a/trlo/src/image-1.png b/trlo/src/image-1.png new file mode 100644 index 0000000..59a9f4c Binary files /dev/null and b/trlo/src/image-1.png differ diff --git a/trlo/src/image.png b/trlo/src/image.png new file mode 100644 index 0000000..42c61cd Binary files /dev/null and b/trlo/src/image.png differ diff --git a/trlo/src/nano_gicp/lsq_registration.cc b/trlo/src/nano_gicp/lsq_registration.cc new file mode 100644 index 0000000..8899a6d --- /dev/null +++ b/trlo/src/nano_gicp/lsq_registration.cc @@ -0,0 +1,46 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * BSD 3-Clause License + * + * Copyright (c) 2020, SMRT-AIST + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +#include +#include +#include + +template class nano_gicp::LsqRegistration; diff --git a/trlo/src/nano_gicp/nano_gicp.cc b/trlo/src/nano_gicp/nano_gicp.cc new file mode 100644 index 0000000..fa127e9 --- /dev/null +++ b/trlo/src/nano_gicp/nano_gicp.cc @@ -0,0 +1,46 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * BSD 3-Clause License + * + * Copyright (c) 2020, SMRT-AIST + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +#include +#include +#include + +template class nano_gicp::NanoGICP; diff --git a/trlo/src/nano_gicp/nanoflann.cc b/trlo/src/nano_gicp/nanoflann.cc new file mode 100644 index 0000000..71e7133 --- /dev/null +++ b/trlo/src/nano_gicp/nanoflann.cc @@ -0,0 +1,46 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +/*************************************************************************************************** + * Software License Agreement (BSD License) + * + * Copyright 2008-2009 Marius Muja (mariusm@cs.ubc.ca). All rights reserved. + * Copyright 2008-2009 David G. Lowe (lowe@cs.ubc.ca). All rights reserved. + * Copyright 2011-2021 Jose Luis Blanco (joseluisblancoc@gmail.com). + * All rights reserved. + * + * THE BSD LICENSE + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES + * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. + * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, + * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY + * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF + * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************************************************/ + +#include +#include +#include + +template class nanoflann::KdTreeFLANN; diff --git a/trlo/src/trlo/ceresFactor.hpp b/trlo/src/trlo/ceresFactor.hpp new file mode 100644 index 0000000..fcbf82f --- /dev/null +++ b/trlo/src/trlo/ceresFactor.hpp @@ -0,0 +1,113 @@ +#pragma once + +#include +#include +#include +#include +#include + + + +template inline +void Quaternion2EulerAngle(const T q[4], T ypr[3]) +{ + // roll (x-axis rotation) + T sinr_cosp = T(2) * (q[0] * q[1] + q[2] * q[3]); + T cosr_cosp = T(1) - T(2) * (q[1] * q[1] + q[2] * q[2]); + ypr[2] = atan2(sinr_cosp, cosr_cosp); + + // pitch (y-axis rotation) + T sinp = T(2) * (q[0] * q[2] - q[1] * q[3]); + if (sinp >= T(1)) + { + ypr[1] = T(M_PI / 2); // use 90 degrees if out of range + } + else if (sinp <= T(-1)) + { + ypr[1] = -T(M_PI / 2); // use 90 degrees if out of range + } + else + { + ypr[1] = asin(sinp); + } + + // yaw (z-axis rotation) + T siny_cosp = T(2) * (q[0] * q[3] + q[1] * q[2]); + T cosy_cosp = T(1) - T(2) * (q[2] * q[2] + q[3] * q[3]); + ypr[0] = atan2(siny_cosp, cosy_cosp); +}; + + +struct PitchRollFactor +{ + PitchRollFactor(double p, double r, double q_var) + : p(p), r(r), q_var(q_var) {} + + template + bool operator()(const T* const q_i, T* residuals) const + { + T q_i_tmp[4]; + q_i_tmp[0] = q_i[3]; // ceres in w, x, y, z order + q_i_tmp[1] = q_i[0]; + q_i_tmp[2] = q_i[1]; + q_i_tmp[3] = q_i[2]; + + T ypr[3]; + Quaternion2EulerAngle(q_i_tmp, ypr); + + T e[2]; + e[0] = ypr[1] - T(p); + e[1] = ypr[2] - T(r); + + residuals[0] = T(2) * e[0] / T(q_var); + residuals[1] = T(2) * e[1] / T(q_var); + + return true; + } + + static ceres::CostFunction* Create(const double p, const double r, const double q_var) + { + return (new ceres::AutoDiffCostFunction(new PitchRollFactor(p, r, q_var))); + } + + double p, r; + double q_var; +}; + + + +struct GroundFactor +{ + GroundFactor(double var, double tz_prev): var(var), tz_prev(tz_prev){} + + template + bool operator()(const T* tz_curr, T* residuals) const + { + residuals[0] = (tz_curr[0] - tz_prev) / T(var); + + return true; + } + + static ceres::CostFunction* Create(const double var, const double tz_prev) + { + return (new ceres::AutoDiffCostFunction(new GroundFactor(var, tz_prev))); + } + + double var; + double tz_prev; +}; + + + + + + + + + + + + + + + diff --git a/trlo/src/trlo/map.cc b/trlo/src/trlo/map.cc new file mode 100644 index 0000000..2165679 --- /dev/null +++ b/trlo/src/trlo/map.cc @@ -0,0 +1,189 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +#include "trlo/map.h" + +std::atomic trlo::MapNode::abort_(false); + + +/** + * Constructor + **/ + +trlo::MapNode::MapNode(ros::NodeHandle node_handle) : nh(node_handle) { + + this->getParams(); + + this->abort_timer = this->nh.createTimer(ros::Duration(0.01), &trlo::MapNode::abortTimerCB, this); + + if (this->publish_full_map_){ + this->publish_timer = this->nh.createTimer(ros::Duration(this->publish_freq_), &trlo::MapNode::publishTimerCB, this); + } + + this->keyframe_sub = this->nh.subscribe("keyframes", 1, &trlo::MapNode::keyframeCB, this); + this->map_pub = this->nh.advertise("map", 1); + + this->save_pcd_srv = this->nh.advertiseService("save_pcd", &trlo::MapNode::savePcd, this); + + // initialize map + this->trlo_map = pcl::PointCloud::Ptr (new pcl::PointCloud); + + ROS_INFO("TRLO Map Node Initialized"); + +} + + +/** + * Destructor + **/ + +trlo::MapNode::~MapNode() { + pcl::PointCloud::Ptr m = + pcl::PointCloud::Ptr (boost::make_shared>(*this->trlo_map)); + + std::string p = "/home/jyp/"; + + std::cout << std::setprecision(2) << "Saving map to " << p + "/trlo_map.pcd" << "... "; std::cout.flush(); + + // save map + int ret = pcl::io::savePCDFileBinary(p + "/trlo_map.pcd", *m); +} + + +/** + * Get Params + **/ + +void trlo::MapNode::getParams() { + + ros::param::param("~trlo/odomNode/odom_frame", this->odom_frame, "odom"); + ros::param::param("~trlo/mapNode/publishFullMap", this->publish_full_map_, true); + ros::param::param("~trlo/mapNode/publishFreq", this->publish_freq_, 1.0); + ros::param::param("~trlo/mapNode/leafSize", this->leaf_size_, 0.5); + + // Get Node NS and Remove Leading Character + std::string ns = ros::this_node::getNamespace(); + ns.erase(0,1); + + // Concatenate Frame Name Strings + this->odom_frame = ns + "/" + this->odom_frame; + +} + + +/** + * Start Map Node + **/ + +void trlo::MapNode::start() { + ROS_INFO("Starting TRLO Map Node"); +} + + +/** + * Stop Map Node + **/ + +void trlo::MapNode::stop() { + ROS_WARN("Stopping TRLO Map Node"); + + // shutdown + ros::shutdown(); +} + + +/** + * Abort Timer Callback + **/ + +void trlo::MapNode::abortTimerCB(const ros::TimerEvent& e) { + if (abort_) { + stop(); + } +} + + +/** + * Publish Timer Callback + **/ + +void trlo::MapNode::publishTimerCB(const ros::TimerEvent& e) { + + if (this->trlo_map->points.size() == this->trlo_map->width * this->trlo_map->height) { + sensor_msgs::PointCloud2 map_ros; + pcl::toROSMsg(*this->trlo_map, map_ros); + map_ros.header.stamp = ros::Time::now(); + map_ros.header.frame_id = this->odom_frame; + this->map_pub.publish(map_ros); + } + +} + + +/** + * Node Callback + **/ + +void trlo::MapNode::keyframeCB(const sensor_msgs::PointCloud2ConstPtr& keyframe) { + + // convert scan to pcl format + pcl::PointCloud::Ptr keyframe_pcl = pcl::PointCloud::Ptr (new pcl::PointCloud); + pcl::fromROSMsg(*keyframe, *keyframe_pcl); + + // voxel filter + this->voxelgrid.setLeafSize(this->leaf_size_, this->leaf_size_, this->leaf_size_); + this->voxelgrid.setInputCloud(keyframe_pcl); + this->voxelgrid.filter(*keyframe_pcl); + + // save keyframe to map + this->map_stamp = keyframe->header.stamp; + *this->trlo_map += *keyframe_pcl; + + if (!this->publish_full_map_) { + if (keyframe_pcl->points.size() == keyframe_pcl->width * keyframe_pcl->height) { + sensor_msgs::PointCloud2 map_ros; + pcl::toROSMsg(*keyframe_pcl, map_ros); + map_ros.header.stamp = ros::Time::now(); + map_ros.header.frame_id = this->odom_frame; + this->map_pub.publish(map_ros); + } + } + +} + +bool trlo::MapNode::savePcd(trlo::save_pcd::Request& req, + trlo::save_pcd::Response& res) { + + pcl::PointCloud::Ptr m = + pcl::PointCloud::Ptr (boost::make_shared>(*this->trlo_map)); + + float leaf_size = req.leaf_size; + std::string p = req.save_path; + + std::cout << std::setprecision(2) << "Saving map to " << p + "/trlo_map.pcd" << "... "; std::cout.flush(); + + // voxelize map + pcl::VoxelGrid vg; + vg.setLeafSize(leaf_size, leaf_size, leaf_size); + vg.setInputCloud(m); + vg.filter(*m); + + // save map + int ret = pcl::io::savePCDFileBinary(p + "/trlo_map.pcd", *m); + res.success = ret == 0; + + if (res.success) { + std::cout << "done" << std::endl; + } else { + std::cout << "failed" << std::endl; + } + + return res.success; + +} diff --git a/trlo/src/trlo/map_node.cc b/trlo/src/trlo/map_node.cc new file mode 100644 index 0000000..2b36dba --- /dev/null +++ b/trlo/src/trlo/map_node.cc @@ -0,0 +1,34 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +#include "trlo/map.h" + +void controlC(int sig) { + + trlo::MapNode::abort(); + +} + +int main(int argc, char** argv) { + + ros::init(argc, argv, "trlo_map_node"); + ros::NodeHandle nh("~"); + + signal(SIGTERM, controlC); + sleep(0.5); + + trlo::MapNode node(nh); + ros::AsyncSpinner spinner(1); + spinner.start(); + node.start(); + ros::waitForShutdown(); + + return 0; + +} diff --git a/trlo/src/trlo/odom.cc b/trlo/src/trlo/odom.cc new file mode 100644 index 0000000..1959e08 --- /dev/null +++ b/trlo/src/trlo/odom.cc @@ -0,0 +1,1848 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +#include "trlo/odom.h" +#include "ceresFactor.hpp" + +std::atomic trlo::OdomNode::abort_(false); + +double first_time = 0; + +Eigen::Vector3f R2ypr(const Eigen::Matrix3f &R) +{ + Eigen::Vector3f n = R.col(0); + Eigen::Vector3f o = R.col(1); + Eigen::Vector3f a = R.col(2); + + Eigen::Vector3f ypr(3); + double y = atan2(n(1), n(0)); + double p = atan2(-n(2), n(0) * cos(y) + n(1) * sin(y)); + double r = atan2(a(0) * sin(y) - a(1) * cos(y), -o(0) * sin(y) + o(1) * cos(y)); + ypr(0) = y; + ypr(1) = p; + ypr(2) = r; + + return ypr / M_PI * 180.0; +} + +template +static Eigen::Matrix ypr2R(const Eigen::MatrixBase &ypr) +{ + typedef typename Derived::Scalar Scalar_t; + + // Scalar_t y = ypr(0) / 180.0 * M_PI; + // Scalar_t p = ypr(1) / 180.0 * M_PI; + // Scalar_t r = ypr(2) / 180.0 * M_PI; + + Scalar_t y = ypr(0); + Scalar_t p = ypr(1); + Scalar_t r = ypr(2); + + Eigen::Matrix Rz; + Rz << cos(y), -sin(y), 0, + sin(y), cos(y), 0, + 0, 0, 1; + + Eigen::Matrix Ry; + Ry << cos(p), 0., sin(p), + 0., 1., 0., + -sin(p), 0., cos(p); + + Eigen::Matrix Rx; + Rx << 1., 0., 0., + 0., cos(r), -sin(r), + 0., sin(r), cos(r); + + return Rz * Ry * Rx; +} + +float NormalizationYawAngle(float angle) +{ + if (angle > M_PI) + angle -= 2 * M_PI; + else if (angle < -M_PI) + angle += 2 * M_PI; + + return angle; +} + + +float NormalizationRollPitchAngle(float angle) +{ + if (angle > M_PI / 2) + angle -= M_PI; + else if (angle < -M_PI / 2) + angle += M_PI; + + return angle; +} + +void NormalizationYPR(Eigen::Vector3f& ypr) { + if (ypr(0) > M_PI) + ypr(0) -= 2 * M_PI; + else if (ypr(0) < -M_PI) + ypr(0) += 2 * M_PI; + + if (ypr(1) > M_PI / 2) + ypr(1) -= M_PI; + else if (ypr(1) < -M_PI / 2) + ypr(1) += M_PI; + + if (ypr(2) > M_PI / 2) + ypr(2) -= M_PI; + else if (ypr(2) < -M_PI / 2) + ypr(2) += M_PI; +} + + +bool comp(std::pair i, std::pair j) {return i.second < j.second;} + +/** + * Constructor + **/ + +trlo::OdomNode::OdomNode(ros::NodeHandle node_handle) : nh(node_handle) { + + this->getParams(); + this->InitParam(); + this->allocateMemory(); + + this->icp_sub = this->nh.subscribe("pointcloud", 1, &trlo::OdomNode::icpCB, this); + this->imu_sub = this->nh.subscribe("imu", 1, &trlo::OdomNode::imuCB, this); + this->box_sub = this->nh.subscribe("box", 1, &trlo::OdomNode::boxCB, this); + + this->odom_pub = this->nh.advertise("odom", 1); + this->trajectory_pub = this->nh.advertise("trajectory", 1); + this->pose_pub = this->nh.advertise("pose", 1); + this->kf_pub = this->nh.advertise("kfs", 1, true); + this->keyframe_pub = this->nh.advertise("keyframe", 1, true); + this->robot_pub = this->nh.advertise("robot", 10); + + this->save_traj_srv = this->nh.advertiseService("save_traj", &trlo::OdomNode::saveTrajectory, this); + + // CPU Specs + char CPUBrandString[0x40]; + memset(CPUBrandString, 0, sizeof(CPUBrandString)); + this->cpu_type = ""; + +#ifdef HAS_CPUID + unsigned int CPUInfo[4] = {0,0,0,0}; + __cpuid(0x80000000, CPUInfo[0], CPUInfo[1], CPUInfo[2], CPUInfo[3]); + unsigned int nExIds = CPUInfo[0]; + for (unsigned int i = 0x80000000; i <= nExIds; ++i) { + __cpuid(i, CPUInfo[0], CPUInfo[1], CPUInfo[2], CPUInfo[3]); + if (i == 0x80000002) + memcpy(CPUBrandString, CPUInfo, sizeof(CPUInfo)); + else if (i == 0x80000003) + memcpy(CPUBrandString + 16, CPUInfo, sizeof(CPUInfo)); + else if (i == 0x80000004) + memcpy(CPUBrandString + 32, CPUInfo, sizeof(CPUInfo)); + } + + this->cpu_type = CPUBrandString; + boost::trim(this->cpu_type); +#endif + + FILE* file; + struct tms timeSample; + char line[128]; + + this->lastCPU = times(&timeSample); + this->lastSysCPU = timeSample.tms_stime; + this->lastUserCPU = timeSample.tms_utime; + + file = fopen("/proc/cpuinfo", "r"); + this->numProcessors = 0; + while(fgets(line, 128, file) != NULL) { + if (strncmp(line, "processor", 9) == 0) this->numProcessors++; + } + fclose(file); + + ROS_INFO("TRLO Odom Node Initialized"); + +} + + +/** + * Destructor + **/ + +trlo::OdomNode::~OdomNode() {} + + +/** + * Odom Node Parameters + **/ + +void trlo::OdomNode::getParams() { + + // Version + ros::param::param("~trlo/version", this->version_, "0.0.0"); + + // Frames + ros::param::param("~trlo/odomNode/odom_frame", this->odom_frame, "odom"); + ros::param::param("~trlo/odomNode/child_frame", this->child_frame, "base_link"); + + // Get Node NS and Remove Leading Character + std::string ns = ros::this_node::getNamespace(); + ns.erase(0,1); + + // Concatenate Frame Name Strings + this->odom_frame = ns + "/" + this->odom_frame; + this->child_frame = ns + "/" + this->child_frame; + + // Gravity alignment + ros::param::param("~trlo/gravityAlign", this->gravity_align_, false); + + // Keyframe Threshold + ros::param::param("~trlo/odomNode/keyframe/threshD", this->keyframe_thresh_dist_, 0.1); + ros::param::param("~trlo/odomNode/keyframe/threshR", this->keyframe_thresh_rot_, 1.0); + + // Submap + ros::param::param("~trlo/odomNode/submap/keyframe/knn", this->submap_knn_, 10); + ros::param::param("~trlo/odomNode/submap/keyframe/kcv", this->submap_kcv_, 10); + ros::param::param("~trlo/odomNode/submap/keyframe/kcc", this->submap_kcc_, 10); + + // Initial Position + ros::param::param("~trlo/odomNode/initialPose/use", this->initial_pose_use_, false); + + double px, py, pz, qx, qy, qz, qw; + ros::param::param("~trlo/odomNode/initialPose/position/x", px, 0.0); + ros::param::param("~trlo/odomNode/initialPose/position/y", py, 0.0); + ros::param::param("~trlo/odomNode/initialPose/position/z", pz, 0.0); + ros::param::param("~trlo/odomNode/initialPose/orientation/w", qw, 1.0); + ros::param::param("~trlo/odomNode/initialPose/orientation/x", qx, 0.0); + ros::param::param("~trlo/odomNode/initialPose/orientation/y", qy, 0.0); + ros::param::param("~trlo/odomNode/initialPose/orientation/z", qz, 0.0); + this->initial_position_ = Eigen::Vector3f(px, py, pz); + this->initial_orientation_ = Eigen::Quaternionf(qw, qx, qy, qz); + + // Crop Box Filter + ros::param::param("~trlo/odomNode/preprocessing/cropBoxFilter/use", this->crop_use_, false); + ros::param::param("~trlo/odomNode/preprocessing/cropBoxFilter/size", this->crop_size_, 1.0); + + // Voxel Grid Filter + ros::param::param("~trlo/odomNode/preprocessing/voxelFilter/scan/use", this->vf_scan_use_, true); + ros::param::param("~trlo/odomNode/preprocessing/voxelFilter/scan/res", this->vf_scan_res_, 0.05); + ros::param::param("~trlo/odomNode/preprocessing/voxelFilter/submap/use", this->vf_submap_use_, false); + ros::param::param("~trlo/odomNode/preprocessing/voxelFilter/submap/res", this->vf_submap_res_, 0.1); + + // Adaptive Parameters + ros::param::param("~trlo/adaptiveParams", this->adaptive_params_use_, false); + + // IMU + ros::param::param("~trlo/imu", this->imu_use_, false); + ros::param::param("~trlo/odomNode/imu/calibTime", this->imu_calib_time_, 3); + ros::param::param("~trlo/odomNode/imu/bufferSize", this->imu_buffer_size_, 2000); + + // BBox + ros::param::param("~trlo/odomNode/box/bufferSize", this->box_buffer_size_, 3); + + // Ground Contrain + ros::param::param("~/trlo/ground", this->ground_use_, true); + ros::param::param("~trlo/odomNode/ground/threshold", this->ground_threshold_, 0.2); + + // GICP + ros::param::param("~trlo/odomNode/gicp/minNumPoints", this->gicp_min_num_points_, 100); + ros::param::param("~trlo/odomNode/gicp/s2s/kCorrespondences", this->gicps2s_k_correspondences_, 20); + ros::param::param("~trlo/odomNode/gicp/s2s/maxCorrespondenceDistance", this->gicps2s_max_corr_dist_, std::sqrt(std::numeric_limits::max())); + ros::param::param("~trlo/odomNode/gicp/s2s/maxIterations", this->gicps2s_max_iter_, 64); + ros::param::param("~trlo/odomNode/gicp/s2s/transformationEpsilon", this->gicps2s_transformation_ep_, 0.0005); + ros::param::param("~trlo/odomNode/gicp/s2s/euclideanFitnessEpsilon", this->gicps2s_euclidean_fitness_ep_, -std::numeric_limits::max()); + ros::param::param("~trlo/odomNode/gicp/s2s/ransac/iterations", this->gicps2s_ransac_iter_, 0); + ros::param::param("~trlo/odomNode/gicp/s2s/ransac/outlierRejectionThresh", this->gicps2s_ransac_inlier_thresh_, 0.05); + ros::param::param("~trlo/odomNode/gicp/s2m/kCorrespondences", this->gicps2m_k_correspondences_, 20); + ros::param::param("~trlo/odomNode/gicp/s2m/maxCorrespondenceDistance", this->gicps2m_max_corr_dist_, std::sqrt(std::numeric_limits::max())); + ros::param::param("~trlo/odomNode/gicp/s2m/maxIterations", this->gicps2m_max_iter_, 64); + ros::param::param("~trlo/odomNode/gicp/s2m/transformationEpsilon", this->gicps2m_transformation_ep_, 0.0005); + ros::param::param("~trlo/odomNode/gicp/s2m/euclideanFitnessEpsilon", this->gicps2m_euclidean_fitness_ep_, -std::numeric_limits::max()); + ros::param::param("~trlo/odomNode/gicp/s2m/ransac/iterations", this->gicps2m_ransac_iter_, 0); + ros::param::param("~trlo/odomNode/gicp/s2m/ransac/outlierRejectionThresh", this->gicps2m_ransac_inlier_thresh_, 0.05); + +} + + +/** + * Initialize Parameters +*/ +void trlo::OdomNode::InitParam() { + this->stop_publish_thread = false; + this->stop_publish_keyframe_thread = false; + this->stop_metrics_thread = false; + this->stop_debug_thread = false; + + this->trlo_initialized = false; + this->imu_calibrated = false; + + this->odom.pose.pose.position.x = 0.; + this->odom.pose.pose.position.y = 0.; + this->odom.pose.pose.position.z = 0.; + this->odom.pose.pose.orientation.w = 1.; + this->odom.pose.pose.orientation.x = 0.; + this->odom.pose.pose.orientation.y = 0.; + this->odom.pose.pose.orientation.z = 0.; + this->odom.pose.covariance = {0.}; + + this->origin = Eigen::Vector3f(0., 0., 0.); + + this->T = Eigen::Matrix4f::Identity(); + this->T_s2s = Eigen::Matrix4f::Identity(); + this->T_s2s_prev = Eigen::Matrix4f::Identity(); + + this->pose_s2s = Eigen::Vector3f(0., 0., 0.); + this->rotq_s2s = Eigen::Quaternionf(1., 0., 0., 0.); + + this->pose = Eigen::Vector3f(0., 0., 0.); + this->rotq = Eigen::Quaternionf(1., 0., 0., 0.); + + this->imu_SE3 = Eigen::Matrix4f::Identity(); + + this->imu_bias.gyro.x = 0.; + this->imu_bias.gyro.y = 0.; + this->imu_bias.gyro.z = 0.; + this->imu_bias.accel.x = 0.; + this->imu_bias.accel.y = 0.; + this->imu_bias.accel.z = 0.; + + this->imu_meas.stamp = 0.; + this->imu_meas.ang_vel.x = 0.; + this->imu_meas.ang_vel.y = 0.; + this->imu_meas.ang_vel.z = 0.; + this->imu_meas.lin_accel.x = 0.; + this->imu_meas.lin_accel.y = 0.; + this->imu_meas.lin_accel.z = 0.; + + this->imu_buffer.set_capacity(this->imu_buffer_size_); + this->box_buffer.set_capacity(this->box_buffer_size_); + this->first_imu_time = 0.; + + this->submap_hasChanged = true; + this->submap_kf_idx_prev.clear(); + + this->source_cloud = nullptr; + this->target_cloud = nullptr; + + this->convex_hull.setDimension(3); + this->concave_hull.setDimension(3); + this->concave_hull.setAlpha(this->keyframe_thresh_dist_); + this->concave_hull.setKeepInformation(true); + + this->gicp_s2s.setCorrespondenceRandomness(this->gicps2s_k_correspondences_); + this->gicp_s2s.setMaxCorrespondenceDistance(this->gicps2s_max_corr_dist_); + this->gicp_s2s.setMaximumIterations(this->gicps2s_max_iter_); + this->gicp_s2s.setTransformationEpsilon(this->gicps2s_transformation_ep_); + this->gicp_s2s.setEuclideanFitnessEpsilon(this->gicps2s_euclidean_fitness_ep_); + this->gicp_s2s.setRANSACIterations(this->gicps2s_ransac_iter_); + this->gicp_s2s.setRANSACOutlierRejectionThreshold(this->gicps2s_ransac_inlier_thresh_); + + this->gicp.setCorrespondenceRandomness(this->gicps2m_k_correspondences_); + this->gicp.setMaxCorrespondenceDistance(this->gicps2m_max_corr_dist_); + this->gicp.setMaximumIterations(this->gicps2m_max_iter_); + this->gicp.setTransformationEpsilon(this->gicps2m_transformation_ep_); + this->gicp.setEuclideanFitnessEpsilon(this->gicps2m_euclidean_fitness_ep_); + this->gicp.setRANSACIterations(this->gicps2m_ransac_iter_); + this->gicp.setRANSACOutlierRejectionThreshold(this->gicps2m_ransac_inlier_thresh_); + + pcl::Registration::KdTreeReciprocalPtr temp; + this->gicp_s2s.setSearchMethodSource(temp, true); + this->gicp_s2s.setSearchMethodTarget(temp, true); + this->gicp.setSearchMethodSource(temp, true); + this->gicp.setSearchMethodTarget(temp, true); + + this->crop.setNegative(true); + this->crop.setMin(Eigen::Vector4f(-this->crop_size_, -this->crop_size_, -this->crop_size_, 1.0)); + this->crop.setMax(Eigen::Vector4f(this->crop_size_, this->crop_size_, this->crop_size_, 1.0)); + + this->vf_scan.setLeafSize(this->vf_scan_res_, this->vf_scan_res_, this->vf_scan_res_); + this->vf_submap.setLeafSize(this->vf_submap_res_, this->vf_submap_res_, this->vf_submap_res_); + + this->metrics.spaciousness.push_back(0.); + + this->ground_normal = Eigen::Vector3f(0., 0., 0.); +} + +/** + * Allocate Memory +*/ +void trlo::OdomNode::allocateMemory() +{ + this->current_scan = pcl::PointCloud::Ptr (new pcl::PointCloud); + this->current_scan_t = pcl::PointCloud::Ptr (new pcl::PointCloud); + + this->keyframe_cloud = pcl::PointCloud::Ptr (new pcl::PointCloud); + this->keyframes_cloud = pcl::PointCloud::Ptr (new pcl::PointCloud); + this->num_keyframes = 0; + + this->submap_cloud = pcl::PointCloud::Ptr (new pcl::PointCloud); +} + +/** + * Start Odom Thread + **/ + +void trlo::OdomNode::start() { + ROS_INFO("Starting TRLO Node"); + + printf("\033[2J\033[1;1H"); + std::cout << std::endl << "==== TRLO v" << this->version_ << " ====" << std::endl << std::endl; + +} + + +/** + * Stop Odom Thread + **/ + +void trlo::OdomNode::stop() { + ROS_WARN("Stopping TRLO Node"); + + this->stop_publish_thread = true; + if (this->publish_thread.joinable()) { + this->publish_thread.join(); + } + + this->stop_publish_keyframe_thread = true; + if (this->publish_keyframe_thread.joinable()) { + this->publish_keyframe_thread.join(); + } + + this->stop_metrics_thread = true; + if (this->metrics_thread.joinable()) { + this->metrics_thread.join(); + } + + this->stop_debug_thread = true; + if (this->debug_thread.joinable()) { + this->debug_thread.join(); + } + + ros::shutdown(); +} + + +/** + * Abort Timer Callback + **/ + +void trlo::OdomNode::abortTimerCB(const ros::TimerEvent& e) { + if (abort_) { + stop(); + } +} + + +/** + * Publish to ROS + **/ + +void trlo::OdomNode::publishToROS() { + this->publishPose(); + this->publishTrajectory(); + this->publishTransform(); + this->publishRobot(); +} + + +/** + * Publish Pose + **/ + +void trlo::OdomNode::publishPose() { + + // Sign flip check + static Eigen::Quaternionf q_diff{1., 0., 0., 0.}; + static Eigen::Quaternionf q_last{1., 0., 0., 0.}; + + q_diff = q_last.conjugate()*this->rotq; + + // If q_diff has negative real part then there was a sign flip + if (q_diff.w() < 0) { + this->rotq.w() = -this->rotq.w(); + this->rotq.vec() = -this->rotq.vec(); + } + + q_last = this->rotq; + + this->odom.pose.pose.position.x = this->pose[0]; + this->odom.pose.pose.position.y = this->pose[1]; + this->odom.pose.pose.position.z = this->pose[2]; + + this->odom.pose.pose.orientation.w = this->rotq.w(); + this->odom.pose.pose.orientation.x = this->rotq.x(); + this->odom.pose.pose.orientation.y = this->rotq.y(); + this->odom.pose.pose.orientation.z = this->rotq.z(); + + this->odom.header.stamp = this->scan_stamp; + this->odom.header.frame_id = this->odom_frame; + this->odom.child_frame_id = this->child_frame; + this->odom_pub.publish(this->odom); + + this->pose_ros.header.stamp = this->scan_stamp; + this->pose_ros.header.frame_id = this->odom_frame; + + this->pose_ros.pose.position.x = this->pose[0]; + this->pose_ros.pose.position.y = this->pose[1]; + this->pose_ros.pose.position.z = this->pose[2]; + + this->pose_ros.pose.orientation.w = this->rotq.w(); + this->pose_ros.pose.orientation.x = this->rotq.x(); + this->pose_ros.pose.orientation.y = this->rotq.y(); + this->pose_ros.pose.orientation.z = this->rotq.z(); + + this->pose_pub.publish(this->pose_ros); +} + + +/** + * Publish Trajectory + **/ +void trlo::OdomNode::publishTrajectory() +{ + geometry_msgs::PoseStamped pose_curr; + pose_curr.header.stamp = this->scan_stamp; + pose_curr.header.frame_id = this->odom_frame; + pose_curr.pose.position.x = this->pose[0]; + pose_curr.pose.position.y = this->pose[1]; + pose_curr.pose.position.z = this->pose[2]; + pose_curr.pose.orientation.w = this->rotq.w(); + pose_curr.pose.orientation.x = this->rotq.x(); + pose_curr.pose.orientation.y = this->rotq.y(); + pose_curr.pose.orientation.z = this->rotq.z(); + + this->robot_trajectory.header.stamp = this->scan_stamp; + this->robot_trajectory.header.frame_id = this->odom_frame; + this->robot_trajectory.poses.push_back(pose_curr); + this->trajectory_pub.publish(this->robot_trajectory); +} + + +/** + * Publish Transform + **/ + +void trlo::OdomNode::publishTransform() { + + static tf2_ros::TransformBroadcaster br; + geometry_msgs::TransformStamped transformStamped; + + transformStamped.header.stamp = this->scan_stamp; + transformStamped.header.frame_id = this->odom_frame; + transformStamped.child_frame_id = this->child_frame; + + transformStamped.transform.translation.x = this->pose[0]; + transformStamped.transform.translation.y = this->pose[1]; + transformStamped.transform.translation.z = this->pose[2]; + + transformStamped.transform.rotation.w = this->rotq.w(); + transformStamped.transform.rotation.x = this->rotq.x(); + transformStamped.transform.rotation.y = this->rotq.y(); + transformStamped.transform.rotation.z = this->rotq.z(); + + br.sendTransform(transformStamped); + +} + + +/** + * Publish Keyframe Pose and Scan + **/ + +void trlo::OdomNode::publishKeyframe() { + + // Publish keyframe pose + this->kf.header.stamp = this->scan_stamp; + this->kf.header.frame_id = this->odom_frame; // odom + this->kf.child_frame_id = this->child_frame; // base_link + + this->kf.pose.pose.position.x = this->pose[0]; + this->kf.pose.pose.position.y = this->pose[1]; + this->kf.pose.pose.position.z = this->pose[2]; + + this->kf.pose.pose.orientation.w = this->rotq.w(); + this->kf.pose.pose.orientation.x = this->rotq.x(); + this->kf.pose.pose.orientation.y = this->rotq.y(); + this->kf.pose.pose.orientation.z = this->rotq.z(); + + this->kf_pub.publish(this->kf); + + // Publish keyframe scan + if (this->keyframe_cloud->points.size() == this->keyframe_cloud->width * this->keyframe_cloud->height) { + sensor_msgs::PointCloud2 keyframe_cloud_ros; + pcl::toROSMsg(*this->keyframe_cloud, keyframe_cloud_ros); + keyframe_cloud_ros.header.stamp = this->scan_stamp; + keyframe_cloud_ros.header.frame_id = this->odom_frame; + this->keyframe_pub.publish(keyframe_cloud_ros); + } + +} + + +/** + * Publish Robot Marker + **/ +void trlo::OdomNode::publishRobot() +{ + visualization_msgs::Marker tempMarker; + tempMarker.id = 0; + + tempMarker.header.frame_id = this->odom_frame; + tempMarker.header.stamp = this->scan_stamp; + tempMarker.id = 0; + tempMarker.ns = "robot"; + tempMarker.type = visualization_msgs::Marker::CUBE; + tempMarker.action = visualization_msgs::Marker::ADD; + + tempMarker.pose.position.x = this->pose[0]; + tempMarker.pose.position.y = this->pose[1]; + tempMarker.pose.position.z = this->pose[2]; + tempMarker.pose.orientation.x = this->rotq.x(); + tempMarker.pose.orientation.y = this->rotq.y(); + tempMarker.pose.orientation.z = this->rotq.z(); + tempMarker.pose.orientation.w = this->rotq.w(); + + tempMarker.scale.x = 3.6; + tempMarker.scale.y = 2.0; + tempMarker.scale.z = 1.5; + + tempMarker.color.r = 1.0f; + tempMarker.color.g = 0.0f; + tempMarker.color.b = 0.0f; + tempMarker.color.a = 1.0; + + tempMarker.lifetime = ros::Duration(); + + this->robot_pub.publish(tempMarker); +} + + +/** + * Preprocessing + **/ + +void trlo::OdomNode::preprocessPoints() { + + // Remove NaNs + std::vector idx; + this->current_scan->is_dense = false; + pcl::removeNaNFromPointCloud(*this->current_scan, *this->current_scan, idx); + //this->removeClosedPointCloud(*this->current_scan, *this->current_scan, 0.5, 80); + + // Crop Box Filter + if (this->crop_use_) { + this->crop.setInputCloud(this->current_scan); + this->crop.filter(*this->current_scan); + } + + // Voxel Grid Filter + if (this->vf_scan_use_) { + this->vf_scan.setInputCloud(this->current_scan); + this->vf_scan.filter(*this->current_scan); + } + +} + +double MINIMUM_RANGE = 0.5, MAXMUM_RANGE = 80; +void trlo::OdomNode::removeClosedPointCloud(const pcl::PointCloud &cloud_in, pcl::PointCloud &cloud_out, float th1, float th2) +{ + if (&cloud_in != &cloud_out) + { + cloud_out.header = cloud_in.header; + cloud_out.points.resize(cloud_in.points.size()); + } + + size_t j = 0; + + for (size_t i = 0; i < cloud_in.points.size(); ++i) + { + float dis = cloud_in.points[i].x * cloud_in.points[i].x + cloud_in.points[i].y * cloud_in.points[i].y + cloud_in.points[i].z * cloud_in.points[i].z; + if (dis < th1 * th1) + continue; + if (dis > th2 * th2) + continue; + cloud_out.points[j++] = cloud_in.points[i]; + } + + if (j != cloud_in.points.size()) + { + cloud_out.points.resize(j); + } + + cloud_out.height = 1; + cloud_out.width = static_cast(j); + cloud_out.is_dense = true; +} + + + + +/** + * Initialize Input Target + **/ + +void trlo::OdomNode::initializeInputTarget() { + + this->prev_frame_stamp = this->curr_frame_stamp; + + // Convert ros message + this->target_cloud = pcl::PointCloud::Ptr (new pcl::PointCloud); + this->target_cloud = this->current_scan; + this->gicp_s2s.setInputTarget(this->target_cloud); + this->gicp_s2s.calculateTargetCovariances(); + + // initialize keyframes + pcl::PointCloud::Ptr first_keyframe (new pcl::PointCloud); + pcl::transformPointCloud (*this->target_cloud, *first_keyframe, this->T); + + // voxelization for submap + if (this->vf_submap_use_) { + this->vf_submap.setInputCloud(first_keyframe); + this->vf_submap.filter(*first_keyframe); + } + + // keep history of keyframes + this->keyframes.push_back(std::make_pair(std::make_pair(this->pose, this->rotq), first_keyframe)); + *this->keyframes_cloud += *first_keyframe; + *this->keyframe_cloud = *first_keyframe; + + // compute kdtree and keyframe normals (use gicp_s2s input source as temporary storage because it will be overwritten by setInputSources()) + this->gicp_s2s.setInputSource(this->keyframe_cloud); + this->gicp_s2s.calculateSourceCovariances(); + this->keyframe_normals.push_back(this->gicp_s2s.getSourceCovariances()); + + this->publish_keyframe_thread = std::thread( &trlo::OdomNode::publishKeyframe, this ); + this->publish_keyframe_thread.detach(); + + ++this->num_keyframes; + +} + + +/** + * Set Input Sources + **/ + +void trlo::OdomNode::setInputSources(){ + + // set the input source for the S2S gicp + // this builds the KdTree of the source cloud + // this does not build the KdTree for s2m because force_no_update is true + this->gicp_s2s.setInputSource(this->current_scan); + + // set pcl::Registration input source for S2M gicp using custom NanoGICP function + this->gicp.registerInputSource(this->current_scan); + + // now set the KdTree of S2M gicp using previously built KdTree + this->gicp.source_kdtree_ = this->gicp_s2s.source_kdtree_; + this->gicp.source_covs_.clear(); + +} + + +/** + * Gravity Alignment + **/ + +void trlo::OdomNode::gravityAlign() { + + // get average acceleration vector for 1 second and normalize + Eigen::Vector3f lin_accel = Eigen::Vector3f::Zero(); + const double then = ros::Time::now().toSec(); + int n=0; + while ((ros::Time::now().toSec() - then) < 1.) { + lin_accel[0] += this->imu_meas.lin_accel.x; + lin_accel[1] += this->imu_meas.lin_accel.y; + lin_accel[2] += this->imu_meas.lin_accel.z; + ++n; + } + lin_accel[0] /= n; lin_accel[1] /= n; lin_accel[2] /= n; + + // normalize + double lin_norm = sqrt(pow(lin_accel[0], 2) + pow(lin_accel[1], 2) + pow(lin_accel[2], 2)); + lin_accel[0] /= lin_norm; lin_accel[1] /= lin_norm; lin_accel[2] /= lin_norm; + + // define gravity vector (assume point downwards) + Eigen::Vector3f grav; + grav << 0, 0, 1; + + // calculate angle between the two vectors + Eigen::Quaternionf grav_q = Eigen::Quaternionf::FromTwoVectors(lin_accel, grav); + + // normalize + double grav_norm = sqrt(grav_q.w()*grav_q.w() + grav_q.x()*grav_q.x() + grav_q.y()*grav_q.y() + grav_q.z()*grav_q.z()); + grav_q.w() /= grav_norm; grav_q.x() /= grav_norm; grav_q.y() /= grav_norm; grav_q.z() /= grav_norm; + + // set gravity aligned orientation + this->rotq = grav_q; + this->T.block(0,0,3,3) = this->rotq.toRotationMatrix(); + this->T_s2s.block(0,0,3,3) = this->rotq.toRotationMatrix(); + this->T_s2s_prev.block(0,0,3,3) = this->rotq.toRotationMatrix(); + + // rpy + auto euler = grav_q.toRotationMatrix().eulerAngles(2, 1, 0); + double yaw = euler[0] * (180.0/M_PI); + double pitch = euler[1] * (180.0/M_PI); + double roll = euler[2] * (180.0/M_PI); + + std::cout << "done" << std::endl; + std::cout << " Roll [deg]: " << roll << std::endl; + std::cout << " Pitch [deg]: " << pitch << std::endl << std::endl; +} + + +/** + * Initialize 6DOF + **/ + +void trlo::OdomNode::initializeTRLO() { + + // Calibrate IMU + if (!this->imu_calibrated && this->imu_use_) { + return; + } + + // Gravity Align + if (this->gravity_align_ && this->imu_use_ && this->imu_calibrated && !this->initial_pose_use_) { + std::cout << "Aligning to gravity... "; std::cout.flush(); + this->gravityAlign(); + } + + // Use initial known pose + if (this->initial_pose_use_) { + std::cout << "Setting known initial pose... "; std::cout.flush(); + + // set known position + this->pose = this->initial_position_; + this->T.block(0,3,3,1) = this->pose; + this->T_s2s.block(0,3,3,1) = this->pose; + this->T_s2s_prev.block(0,3,3,1) = this->pose; + this->origin = this->initial_position_; + + // set known orientation + this->rotq = this->initial_orientation_; + this->T.block(0,0,3,3) = this->rotq.toRotationMatrix(); + this->T_s2s.block(0,0,3,3) = this->rotq.toRotationMatrix(); + this->T_s2s_prev.block(0,0,3,3) = this->rotq.toRotationMatrix(); + + std::cout << "done" << std::endl << std::endl; + } + + this->trlo_initialized = true; + std::cout << "TRLO initialized! Starting localization..." << std::endl; + +} + + +/** + * ICP Point Cloud Callback + **/ + +void trlo::OdomNode::icpCB(const sensor_msgs::PointCloud2ConstPtr& pc) { + + double then = ros::Time::now().toSec(); + this->scan_stamp = pc->header.stamp; + this->curr_frame_stamp = pc->header.stamp.toSec(); + + // If there are too few points in the pointcloud, try again + this->current_scan = pcl::PointCloud::Ptr (new pcl::PointCloud); + pcl::fromROSMsg(*pc, *this->current_scan); + if (this->current_scan->points.size() < this->gicp_min_num_points_) { + ROS_WARN("Low number of points!"); + return; + } + + // TRLO Initialization procedures (IMU calib, gravity align) + if (!this->trlo_initialized) { + this->initializeTRLO(); + return; + } + + // Preprocess points + this->preprocessPoints(); + + // Compute Metrics + this->metrics_thread = std::thread( &trlo::OdomNode::computeMetrics, this ); + this->metrics_thread.detach(); + + // Set Adaptive Parameters + if (this->adaptive_params_use_){ + this->setAdaptiveParams(); + } + + // Set initial frame as target + if(this->target_cloud == nullptr) { + this->initializeInputTarget(); + return; + } + + // Set source frame + this->source_cloud = pcl::PointCloud::Ptr (new pcl::PointCloud); + this->source_cloud = this->current_scan; + + // Set new frame as input source for both gicp objects + this->setInputSources(); + + // Get the next pose via IMU + S2S + S2M + this->getNextPose(); + + // Update current keyframe poses and map + this->updateKeyframes(); + + // Update trajectory + this->trajectory.push_back( std::make_pair(this->pose, this->rotq) ); + + // Update next time stamp + this->prev_frame_stamp = this->curr_frame_stamp; + + // Update some statistics + this->comp_times.push_back(ros::Time::now().toSec() - then); + + // Publish stuff to ROS + this->publish_thread = std::thread( &trlo::OdomNode::publishToROS, this ); + this->publish_thread.detach(); + + // Debug statements and publish custom trlo message + this->debug_thread = std::thread( &trlo::OdomNode::debug, this ); + this->debug_thread.detach(); + +} + + +/** + * IMU Callback + **/ + +void trlo::OdomNode::imuCB(const sensor_msgs::Imu::ConstPtr& imu) { + + if (!this->imu_use_) { + return; + } + + double ang_vel[3], lin_accel[3]; + + // Get IMU samples + ang_vel[0] = imu->angular_velocity.x; + ang_vel[1] = imu->angular_velocity.y; + ang_vel[2] = imu->angular_velocity.z; + + lin_accel[0] = imu->linear_acceleration.x; + lin_accel[1] = imu->linear_acceleration.y; + lin_accel[2] = imu->linear_acceleration.z; + + if (this->first_imu_time == 0.) { + this->first_imu_time = imu->header.stamp.toSec(); + } + + // IMU calibration procedure - do for three seconds + if (!this->imu_calibrated) { + + static int num_samples = 0; + static bool print = true; + + if ((imu->header.stamp.toSec() - this->first_imu_time) < this->imu_calib_time_) { + + num_samples++; + + this->imu_bias.gyro.x += ang_vel[0]; + this->imu_bias.gyro.y += ang_vel[1]; + this->imu_bias.gyro.z += ang_vel[2]; + + this->imu_bias.accel.x += lin_accel[0]; + this->imu_bias.accel.y += lin_accel[1]; + this->imu_bias.accel.z += lin_accel[2]; + + if(print) { + std::cout << "Calibrating IMU for " << this->imu_calib_time_ << " seconds... "; std::cout.flush(); + print = false; + } + + } else { + + this->imu_bias.gyro.x /= num_samples; + this->imu_bias.gyro.y /= num_samples; + this->imu_bias.gyro.z /= num_samples; + + this->imu_bias.accel.x /= num_samples; + this->imu_bias.accel.y /= num_samples; + this->imu_bias.accel.z /= num_samples; + + this->imu_calibrated = true; + + std::cout << "done" << std::endl; + std::cout << " Gyro biases [xyz]: " << this->imu_bias.gyro.x << ", " << this->imu_bias.gyro.y << ", " << this->imu_bias.gyro.z << std::endl << std::endl; + + } + + } else { + + // Apply the calibrated bias to the new IMU measurements + this->imu_meas.stamp = imu->header.stamp.toSec(); + + this->imu_meas.ang_vel.x = ang_vel[0] - this->imu_bias.gyro.x; + this->imu_meas.ang_vel.y = ang_vel[1] - this->imu_bias.gyro.y; + this->imu_meas.ang_vel.z = ang_vel[2] - this->imu_bias.gyro.z; + + this->imu_meas.lin_accel.x = lin_accel[0]; + this->imu_meas.lin_accel.y = lin_accel[1]; + this->imu_meas.lin_accel.z = lin_accel[2]; + + // Store into circular buffer + this->mtx_imu.lock(); + this->imu_buffer.push_front(this->imu_meas); + this->mtx_imu.unlock(); + } + +} + + +/** + * BOX Callback +*/ + +void trlo::OdomNode::boxCB(const jsk_recognition_msgs::BoundingBoxArrayPtr& box) { + this->mtx_box.lock(); + this->box_buffer.push_front(*box); + this->mtx_box.unlock(); +} + + + +/** + * Get Next Pose + **/ + +void trlo::OdomNode::getNextPose() { + + // + // FRAME-TO-FRAME PROCEDURE + // + + // Align using IMU prior if available + pcl::PointCloud::Ptr aligned (new pcl::PointCloud); + + if (this->imu_use_) { + this->integrateIMU(); + this->gicp_s2s.align(*aligned, this->imu_SE3); + } else { + this->gicp_s2s.align(*aligned); + } + + // Get the local S2S transform + Eigen::Matrix4f T_S2S = this->gicp_s2s.getFinalTransformation(); + + // Get the global S2S transform + this->propagateS2S(T_S2S); + + // reuse covariances from s2s for s2m + this->gicp.source_covs_ = this->gicp_s2s.source_covs_; + + // Swap source and target (which also swaps KdTrees internally) for next S2S + this->gicp_s2s.swapSourceAndTarget(); + + // + // FRAME-TO-SUBMAP + // + + // Get current global submap + this->getSubmapKeyframes(); + + if (this->submap_hasChanged) { + + // Set the current global submap as the target cloud + this->gicp.setInputTarget(this->submap_cloud); + + // Set target cloud's normals as submap normals + this->gicp.setTargetCovariances( this->submap_normals ); + } + + // Align with current submap with global S2S transformation as initial guess + this->gicp.align(*aligned, this->T_s2s); + + // Get final transformation in global frame + this->T = this->gicp.getFinalTransformation(); + + + if (!this->box_buffer.empty()) + { + double cur_box_z = 0; + double pre_box_z = 0; + std::vector groundPoints; + for (auto box : this->box_buffer.front().boxes) { + cur_box_z += box.pose.position.z; + + Eigen::Vector3f gp; + gp[0] = box.pose.position.x; + gp[1] = box.pose.position.y; + gp[2] = box.pose.position.z - box.dimensions.z / 2; + groundPoints.push_back(gp); + } + cur_box_z /= this->box_buffer.front().boxes.size(); + for (auto box : this->box_buffer[1].boxes) { + pre_box_z += box.pose.position.z; + + Eigen::Vector3f gp; + gp(0) = box.pose.position.x; + gp(1) = box.pose.position.y; + gp(2) = box.pose.position.z - box.dimensions.z / 2; + groundPoints.push_back(gp); + } + pre_box_z /= this->box_buffer[1].boxes.size(); + + + // extract ground normal + int groundPointsSize = groundPoints.size(); + Eigen::Matrix matA0; + Eigen::Matrix matB0; + + matA0.resize(groundPointsSize, 3); + matB0.setOnes(groundPointsSize, 1); + matB0 = -1 * matB0; + + for (int i = 0; i < groundPointsSize; i++) { + matA0(i, 0) = groundPoints[i](0); + matA0(i, 1) = groundPoints[i](1); + matA0(i, 2) = groundPoints[i](2); + } + + // find the norm of plane + this->ground_normal = matA0.colPivHouseholderQr().solve(matB0); + this->ground_normal = this->T.block<3,3>(0,0) * this->ground_normal + this->T.block<3,1>(0,3); + float negative_OA_dot_norm = 1 / this->ground_normal.norm(); + this->ground_normal.normalize(); + + // calculate angle between the two vectors + Eigen::Vector3f grav(0, 0, 1); + Eigen::Quaternionf ground_q = Eigen::Quaternionf::FromTwoVectors(this->ground_normal, grav); + ground_q.normalize(); + + Eigen::Vector3f ground_ypr = ground_q.toRotationMatrix().eulerAngles(2, 1, 0); + + // Here n(pa, pb, pc) is unit norm of plane + bool planeValid = true; + for (int i = 0; i < groundPointsSize; i++) + { + // if OX * n > 0.2, then plane is not fit well + if (fabs(this->ground_normal(0) * groundPoints[i](0) + + this->ground_normal(1) * groundPoints[i](1) + + this->ground_normal(2) * groundPoints[i](2) + negative_OA_dot_norm) > this->ground_threshold_) + { + planeValid = false; + break; + } + } + + + + this->para_tz[0] = static_cast(this->T(2,3)); + Eigen::Quaternionf q_tem(this->T.block<3,3>(0,0)); + q_tem.normalize(); + this->para_q[0] = static_cast(q_tem.x()); + this->para_q[1] = static_cast(q_tem.y()); + this->para_q[2] = static_cast(q_tem.z()); + this->para_q[3] = static_cast(q_tem.w()); + + ceres::LossFunction *loss_function = new ceres::HuberLoss(0.1); + ceres::Problem::Options problem_options; + + ceres::Problem problem(problem_options); + problem.AddParameterBlock(this->para_tz, 1); + problem.AddParameterBlock(this->para_q, 4); + + if (this->ground_use_ && !this->box_buffer.empty()) { + // constraint + if (planeValid) + { + ceres::CostFunction* Gravity_factor = PitchRollFactor::Create(ground_ypr[1], ground_ypr[2], 0.02); + problem.AddResidualBlock(Gravity_factor, NULL, this->para_q); + } + + double ground_cov = 40000; + Eigen::Vector3f ypr = R2ypr(Eigen::Matrix3f(this->T.block<3,3>(0,0))); + if ((cur_box_z - pre_box_z) < 0.5) { + ground_cov = 0.01; // 0.0001 + } + if ((fabs(ypr.y()) < 5.0) && ((cur_box_z - pre_box_z) < this->ground_threshold_)) + { + ground_cov = 0.00001; // 0.000001 + } + + ceres::CostFunction* Ground_factor = GroundFactor::Create(ground_cov, this->para_tz_pre); + problem.AddResidualBlock(Ground_factor, NULL, this->para_tz); + } + double tg = ros::Time::now().toSec(); + ceres::Solver::Options options; + options.linear_solver_type = ceres::DENSE_QR; + options.max_num_iterations = 6; + options.minimizer_progress_to_stdout = false; + options.check_gradients = false; + options.gradient_check_relative_precision = 1e-4; + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + this->ground_optimize_times.push_back(ros::Time::now().toSec() - tg); + + this->T(2,3) = static_cast(this->para_tz[0]); + Eigen::Vector3f raw_rpy = q_tem.toRotationMatrix().eulerAngles(2, 1, 0); + q_tem.w() = static_cast(this->para_q[3]); + q_tem.x() = static_cast(this->para_q[0]); + q_tem.y() = static_cast(this->para_q[1]); + q_tem.z() = static_cast(this->para_q[2]); + q_tem.normalize(); + Eigen::Vector3f opt_rpy = q_tem.toRotationMatrix().eulerAngles(2, 1, 0); + raw_rpy[1] = opt_rpy[1]; //pitch + raw_rpy[2] = opt_rpy[2]; //roll + + // this->T.block<3,3>(0,0) = ypr2R(raw_rpy); + + para_tz_pre = this->T(2,3); + } + + // Update the S2S transform for next propagation + this->T_s2s_prev = this->T; + + // Update next global pose + // Both source and target clouds are in the global frame now, so tranformation is global + this->propagateS2M(); + + // Set next target cloud as current source cloud + *this->target_cloud = *this->source_cloud; + +} + + +/** + * Integrate IMU + **/ + +void trlo::OdomNode::integrateIMU() { + + // Extract IMU data between the two frames + std::vector imu_frame; + + for (const auto& i : this->imu_buffer) { + + // IMU data between two frames is when: + // current frame's timestamp minus imu timestamp is positive + // previous frame's timestamp minus imu timestamp is negative + double curr_frame_imu_dt = this->curr_frame_stamp - i.stamp; + double prev_frame_imu_dt = this->prev_frame_stamp - i.stamp; + + if (curr_frame_imu_dt >= 0. && prev_frame_imu_dt <= 0.) { + + imu_frame.push_back(i); + + } + + } + + // Sort measurements by time(升序) + std::sort(imu_frame.begin(), imu_frame.end(), this->comparatorImu); + + // Relative IMU integration of gyro and accelerometer + double curr_imu_stamp = 0.; + double prev_imu_stamp = 0.; + double dt; + + Eigen::Quaternionf q = Eigen::Quaternionf::Identity(); + + for (uint32_t i = 0; i < imu_frame.size(); ++i) { + + if (prev_imu_stamp == 0.) { + prev_imu_stamp = imu_frame[i].stamp; + continue; + } + + // Calculate difference in imu measurement times IN SECONDS + curr_imu_stamp = imu_frame[i].stamp; + dt = curr_imu_stamp - prev_imu_stamp; + prev_imu_stamp = curr_imu_stamp; + + // Relative gyro propagation quaternion dynamics + Eigen::Quaternionf qq = q; + q.w() -= 0.5*( qq.x()*imu_frame[i].ang_vel.x + qq.y()*imu_frame[i].ang_vel.y + qq.z()*imu_frame[i].ang_vel.z ) * dt; + q.x() += 0.5*( qq.w()*imu_frame[i].ang_vel.x - qq.z()*imu_frame[i].ang_vel.y + qq.y()*imu_frame[i].ang_vel.z ) * dt; + q.y() += 0.5*( qq.z()*imu_frame[i].ang_vel.x + qq.w()*imu_frame[i].ang_vel.y - qq.x()*imu_frame[i].ang_vel.z ) * dt; + q.z() += 0.5*( qq.x()*imu_frame[i].ang_vel.y - qq.y()*imu_frame[i].ang_vel.x + qq.w()*imu_frame[i].ang_vel.z ) * dt; + + } + + // Normalize quaternion + double norm = sqrt(q.w()*q.w() + q.x()*q.x() + q.y()*q.y() + q.z()*q.z()); + q.w() /= norm; q.x() /= norm; q.y() /= norm; q.z() /= norm; + + // Store IMU guess + this->imu_SE3 = Eigen::Matrix4f::Identity(); + this->imu_SE3.block(0, 0, 3, 3) = q.toRotationMatrix(); + +} + + +/** + * Propagate S2S Alignment + **/ + +void trlo::OdomNode::propagateS2S(Eigen::Matrix4f T) { + + this->T_s2s = this->T_s2s_prev * T; + this->T_s2s_prev = this->T_s2s; + + this->pose_s2s << this->T_s2s(0,3), this->T_s2s(1,3), this->T_s2s(2,3); + this->rotSO3_s2s << this->T_s2s(0,0), this->T_s2s(0,1), this->T_s2s(0,2), + this->T_s2s(1,0), this->T_s2s(1,1), this->T_s2s(1,2), + this->T_s2s(2,0), this->T_s2s(2,1), this->T_s2s(2,2); + + Eigen::Quaternionf q(this->rotSO3_s2s); + + // Normalize quaternion + double norm = sqrt(q.w()*q.w() + q.x()*q.x() + q.y()*q.y() + q.z()*q.z()); + q.w() /= norm; q.x() /= norm; q.y() /= norm; q.z() /= norm; + this->rotq_s2s = q; + +} + + +/** + * Propagate S2M Alignment + **/ + +void trlo::OdomNode::propagateS2M() { + + this->pose << this->T(0,3), this->T(1,3), this->T(2,3); + this->rotSO3 << this->T(0,0), this->T(0,1), this->T(0,2), + this->T(1,0), this->T(1,1), this->T(1,2), + this->T(2,0), this->T(2,1), this->T(2,2); + + Eigen::Quaternionf q(this->rotSO3); + + // Normalize quaternion + double norm = sqrt(q.w()*q.w() + q.x()*q.x() + q.y()*q.y() + q.z()*q.z()); + q.w() /= norm; q.x() /= norm; q.y() /= norm; q.z() /= norm; + this->rotq = q; + +} + + +/** + * Transform Current Scan + **/ + +void trlo::OdomNode::transformCurrentScan() { + this->current_scan_t = pcl::PointCloud::Ptr (new pcl::PointCloud); + pcl::transformPointCloud (*this->current_scan, *this->current_scan_t, this->T); +} + + +/** + * Compute Metrics + **/ + +void trlo::OdomNode::computeMetrics() { + this->computeSpaciousness(); +} + + +/** + * Compute Spaciousness of Current Scan + **/ + +void trlo::OdomNode::computeSpaciousness() { + + // compute range of points + std::vector ds; + + for (int i = 0; i <= this->current_scan->points.size(); i++) { + float d = std::sqrt(pow(this->current_scan->points[i].x, 2) + pow(this->current_scan->points[i].y, 2) + pow(this->current_scan->points[i].z, 2)); + ds.push_back(d); + } + + // median + std::nth_element(ds.begin(), ds.begin() + ds.size()/2, ds.end()); + float median_curr = ds[ds.size()/2]; + static float median_prev = median_curr; + float median_lpf = 0.95*median_prev + 0.05*median_curr; + median_prev = median_lpf; + + // push + this->metrics.spaciousness.push_back( median_lpf ); + +} + + +/** + * Convex Hull of Keyframes + **/ + +void trlo::OdomNode::computeConvexHull() { + + // at least 4 keyframes for convex hull + if (this->num_keyframes < 4) { + return; + } + + // create a pointcloud with points at keyframes + pcl::PointCloud::Ptr cloud = pcl::PointCloud::Ptr (new pcl::PointCloud); + + for (const auto& k : this->keyframes) { + PointType pt; + pt.x = k.first.first[0]; + pt.y = k.first.first[1]; + pt.z = k.first.first[2]; + cloud->push_back(pt); + } + + // calculate the convex hull of the point cloud + this->convex_hull.setInputCloud(cloud); + + // get the indices of the keyframes on the convex hull + pcl::PointCloud::Ptr convex_points = pcl::PointCloud::Ptr (new pcl::PointCloud); + this->convex_hull.reconstruct(*convex_points); + + pcl::PointIndices::Ptr convex_hull_point_idx = pcl::PointIndices::Ptr (new pcl::PointIndices); + this->convex_hull.getHullPointIndices(*convex_hull_point_idx); + + this->keyframe_convex.clear(); + for (int i=0; iindices.size(); ++i) { + this->keyframe_convex.push_back(convex_hull_point_idx->indices[i]); + } + +} + + +/** + * Concave Hull of Keyframes + **/ + +void trlo::OdomNode::computeConcaveHull() { + + // at least 5 keyframes for concave hull + if (this->num_keyframes < 5) { + return; + } + + // create a pointcloud with points at keyframes + pcl::PointCloud::Ptr cloud = pcl::PointCloud::Ptr (new pcl::PointCloud); + + for (const auto& k : this->keyframes) { + PointType pt; + pt.x = k.first.first[0]; + pt.y = k.first.first[1]; + pt.z = k.first.first[2]; + cloud->push_back(pt); + } + + // calculate the concave hull of the point cloud + this->concave_hull.setInputCloud(cloud); + + // get the indices of the keyframes on the concave hull + pcl::PointCloud::Ptr concave_points = pcl::PointCloud::Ptr (new pcl::PointCloud); + this->concave_hull.reconstruct(*concave_points); + + pcl::PointIndices::Ptr concave_hull_point_idx = pcl::PointIndices::Ptr (new pcl::PointIndices); + this->concave_hull.getHullPointIndices(*concave_hull_point_idx); + + this->keyframe_concave.clear(); + for (int i=0; iindices.size(); ++i) { + this->keyframe_concave.push_back(concave_hull_point_idx->indices[i]); + } + +} + + +/** + * Update keyframes + **/ + +void trlo::OdomNode::updateKeyframes() { + + // transform point cloud + this->transformCurrentScan(); + + // calculate difference in pose and rotation to all poses in trajectory + float closest_d = std::numeric_limits::infinity(); + int closest_idx = 0; + int keyframes_idx = 0; + + int num_nearby = 0; + + for (const auto& k : this->keyframes) { + + // calculate distance between current pose and pose in keyframes + float delta_d = sqrt( pow(this->pose[0] - k.first.first[0], 2) + pow(this->pose[1] - k.first.first[1], 2) + pow(this->pose[2] - k.first.first[2], 2) ); + + // count the number nearby current pose + if (delta_d <= this->keyframe_thresh_dist_ * 1.5){ + ++num_nearby; + } + + // store into variable + if (delta_d < closest_d) { + closest_d = delta_d; + closest_idx = keyframes_idx; + } + + keyframes_idx++; + + } + + // get closest pose and corresponding rotation + Eigen::Vector3f closest_pose = this->keyframes[closest_idx].first.first; + Eigen::Quaternionf closest_pose_r = this->keyframes[closest_idx].first.second; + + // calculate distance between current pose and closest pose from above + float dd = sqrt( pow(this->pose[0] - closest_pose[0], 2) + pow(this->pose[1] - closest_pose[1], 2) + pow(this->pose[2] - closest_pose[2], 2) ); + + // calculate difference in orientation + Eigen::Quaternionf dq = this->rotq * (closest_pose_r.inverse()); + + float theta_rad = 2. * atan2(sqrt( pow(dq.x(), 2) + pow(dq.y(), 2) + pow(dq.z(), 2) ), dq.w()); + float theta_deg = theta_rad * (180.0/M_PI); + + // update keyframe + bool newKeyframe = false; + + if (abs(dd) > this->keyframe_thresh_dist_ || abs(theta_deg) > this->keyframe_thresh_rot_) { + newKeyframe = true; + } + if (abs(dd) <= this->keyframe_thresh_dist_) { + newKeyframe = false; + } + if (abs(dd) <= this->keyframe_thresh_dist_ && abs(theta_deg) > this->keyframe_thresh_rot_ && num_nearby <= 1) { + newKeyframe = true; + } + + if (newKeyframe) { + + ++this->num_keyframes; + + // voxelization for submap + if (this->vf_submap_use_) { + this->vf_submap.setInputCloud(this->current_scan_t); + this->vf_submap.filter(*this->current_scan_t); + } + + // update keyframe vector + this->keyframes.push_back(std::make_pair(std::make_pair(this->pose, this->rotq), this->current_scan_t)); + + // compute kdtree and keyframe normals (use gicp_s2s input source as temporary storage because it will be overwritten by setInputSources()) + *this->keyframes_cloud += *this->current_scan_t; + *this->keyframe_cloud = *this->current_scan_t; + + this->gicp_s2s.setInputSource(this->keyframe_cloud); + this->gicp_s2s.calculateSourceCovariances(); + this->keyframe_normals.push_back(this->gicp_s2s.getSourceCovariances()); + + this->publish_keyframe_thread = std::thread( &trlo::OdomNode::publishKeyframe, this ); + this->publish_keyframe_thread.detach(); + + } +} + + +/** + * Set Adaptive Parameters + **/ + +void trlo::OdomNode::setAdaptiveParams() { + + // Set Keyframe Thresh from Spaciousness Metric + if (this->metrics.spaciousness.back() > 20.0){ + this->keyframe_thresh_dist_ = 10.0; + } else if (this->metrics.spaciousness.back() > 10.0 && this->metrics.spaciousness.back() <= 20.0) { + this->keyframe_thresh_dist_ = 5.0; + } else if (this->metrics.spaciousness.back() > 5.0 && this->metrics.spaciousness.back() <= 10.0) { + this->keyframe_thresh_dist_ = 1.0; + } else if (this->metrics.spaciousness.back() <= 5.0) { + this->keyframe_thresh_dist_ = 0.5; + } + + // set concave hull alpha + this->concave_hull.setAlpha(this->keyframe_thresh_dist_); + +} + + +/** + * Push Submap Keyframe Indices + **/ +void trlo::OdomNode::pushSubmapIndices(std::vector dists, int k, std::vector frames) { + + // make sure dists is not empty + if (!dists.size()) { return; } + + // maintain max heap of at most k elements + std::priority_queue pq; + + for (auto d : dists) { + if (pq.size() >= k && pq.top() > d) { + pq.push(d); + pq.pop(); + } else if (pq.size() < k) { + pq.push(d); + } + } + + // get the kth smallest element, which should be at the top of the heap + float kth_element = pq.top(); + + // get all elements smaller or equal to the kth smallest element + for (int i = 0; i < dists.size(); ++i) { + if (dists[i] <= kth_element) + // this->submap_kf_idx_curr.push_back(frames[i]); + this->submap_kf_idx_hash.insert(frames[i]); + } + +} + + + +/** + * Get Submap using Nearest Neighbor Keyframes + **/ + +void trlo::OdomNode::getSubmapKeyframes() { + + double submap_build_time = ros::Time::now().toSec(); + + // clear vector of keyframe indices to use for submap + this->submap_kf_idx_curr.clear(); + this->submap_kf_idx_hash.clear(); + + // + // TOP K NEAREST NEIGHBORS FROM ALL KEYFRAMES + // + + // calculate distance between current pose and poses in keyframe set + std::vector ds; + std::vector keyframe_nn; int i=0; + Eigen::Vector3f curr_pose = this->T_s2s.block(0,3,3,1); + + for (const auto& k : this->keyframes) { + float d = sqrt( pow(curr_pose[0] - k.first.first[0], 2) + pow(curr_pose[1] - k.first.first[1], 2) + pow(curr_pose[2] - k.first.first[2], 2) ); + ds.push_back(d); + keyframe_nn.push_back(i); i++; + } + + // get indices for top K nearest neighbor keyframe poses + this->pushSubmapIndices(ds, this->submap_knn_, keyframe_nn); + + // + // TOP K NEAREST NEIGHBORS FROM CONVEX HULL + // + + // get convex hull indices + this->computeConvexHull(); + + // get distances for each keyframe on convex hull + std::vector convex_ds; + for (const auto& c : this->keyframe_convex) { + convex_ds.push_back(ds[c]); + } + + // get indicies for top kNN for convex hull + this->pushSubmapIndices(convex_ds, this->submap_kcv_, this->keyframe_convex); + + // + // TOP K NEAREST NEIGHBORS FROM CONCAVE HULL + // + + // get concave hull(凹包) indices + this->computeConcaveHull(); + + // get distances for each keyframe on concave hull + std::vector concave_ds; + for (const auto& c : this->keyframe_concave) { + concave_ds.push_back(ds[c]); + } + + // get indicies for top kNN for convex hull + this->pushSubmapIndices(concave_ds, this->submap_kcc_, this->keyframe_concave); + + // + // BUILD SUBMAP + // + + for (auto i : this->submap_kf_idx_hash){ + this->submap_kf_idx_curr.push_back(i); + } + + // sort current and previous submap kf list of indices + std::sort(this->submap_kf_idx_curr.begin(), this->submap_kf_idx_curr.end()); + std::sort(this->submap_kf_idx_prev.begin(), this->submap_kf_idx_prev.end()); + + // check if submap has changed from previous iteration + if (this->submap_kf_idx_curr == this->submap_kf_idx_prev){ + this->submap_hasChanged = false; + } else { + this->submap_hasChanged = true; + + // reinitialize submap cloud, normals + pcl::PointCloud::Ptr submap_cloud_ (boost::make_shared>()); + this->submap_normals.clear(); + + for (auto k : this->submap_kf_idx_curr) { + + // create current submap cloud + *submap_cloud_ += *this->keyframes[k].second; + + // grab corresponding submap cloud's normals + this->submap_normals.insert( std::end(this->submap_normals), std::begin(this->keyframe_normals[k]), std::end(this->keyframe_normals[k]) ); + } + + this->submap_cloud = submap_cloud_; + this->submap_kf_idx_prev = this->submap_kf_idx_curr; + } + + this->submap_build_times.push_back(ros::Time::now().toSec() - submap_build_time); + +} + +bool trlo::OdomNode::saveTrajectory(trlo::save_traj::Request& req, + trlo::save_traj::Response& res) { + std::string kittipath = req.save_path + "/kitti_traj.txt"; + std::ofstream out_kitti(kittipath); + + std::cout << std::setprecision(2) << "Saving KITTI trajectory to " << kittipath << "... "; std::cout.flush(); + + for (const auto& pose : this->trajectory) { + const auto& t = pose.first; + const auto& q = pose.second; + // Write to Kitti Format + auto R = q.normalized().toRotationMatrix(); + out_kitti << std::fixed << std::setprecision(9) + << R(0, 0) << " " << R(0, 1) << " " << R(0, 2) << " " << t.x() << " " + << R(1, 0) << " " << R(1, 1) << " " << R(1, 2) << " " << t.y() << " " + << R(2, 0) << " " << R(2, 1) << " " << R(2, 2) << " " << t.z() << "\n"; + } + + std::cout << "done" << std::endl; + res.success = true; + return res.success; +} + +/** + * Debug Statements + **/ + +void trlo::OdomNode::debug() { + + // Total length traversed + double length_traversed = 0.; + Eigen::Vector3f p_curr = Eigen::Vector3f(0., 0., 0.); + Eigen::Vector3f p_prev = Eigen::Vector3f(0., 0., 0.); + for (const auto& t : this->trajectory) { + if (p_prev == Eigen::Vector3f(0., 0., 0.)) { + p_prev = t.first; + continue; + } + p_curr = t.first; + double l = sqrt(pow(p_curr[0] - p_prev[0], 2) + pow(p_curr[1] - p_prev[1], 2) + pow(p_curr[2] - p_prev[2], 2)); + + if (l >= 0.05) { + length_traversed += l; + p_prev = p_curr; + } + } + + if (length_traversed == 0) { + this->publish_keyframe_thread = std::thread( &trlo::OdomNode::publishKeyframe, this ); + this->publish_keyframe_thread.detach(); + } + + // Average computation time + double avg_comp_time = std::accumulate(this->comp_times.begin(), this->comp_times.end(), 0.0) / this->comp_times.size(); + double avg_submap_build_time = std::accumulate(this->submap_build_times.begin(), this->submap_build_times.end(), 0.0) / this->submap_build_times.size(); + double avg_ground_optimize_time = std::accumulate(this->ground_optimize_times.begin(), this->ground_optimize_times.end(), 0.0) / this->ground_optimize_times.size(); + + // RAM Usage + double vm_usage = 0.0; + double resident_set = 0.0; + std::ifstream stat_stream("/proc/self/stat", std::ios_base::in); //get info from proc directory + std::string pid, comm, state, ppid, pgrp, session, tty_nr; + std::string tpgid, flags, minflt, cminflt, majflt, cmajflt; + std::string utime, stime, cutime, cstime, priority, nice; + std::string num_threads, itrealvalue, starttime; + unsigned long vsize; + long rss; + stat_stream >> pid >> comm >> state >> ppid >> pgrp >> session >> tty_nr + >> tpgid >> flags >> minflt >> cminflt >> majflt >> cmajflt + >> utime >> stime >> cutime >> cstime >> priority >> nice + >> num_threads >> itrealvalue >> starttime >> vsize >> rss; // don't care about the rest + stat_stream.close(); + long page_size_kb = sysconf(_SC_PAGE_SIZE) / 1024; // for x86-64 is configured to use 2MB pages + vm_usage = vsize / 1024.0; + resident_set = rss * page_size_kb; + + // CPU Usage + struct tms timeSample; + clock_t now; + double cpu_percent; + now = times(&timeSample); + if (now <= this->lastCPU || timeSample.tms_stime < this->lastSysCPU || + timeSample.tms_utime < this->lastUserCPU) { + cpu_percent = -1.0; + } else { + cpu_percent = (timeSample.tms_stime - this->lastSysCPU) + (timeSample.tms_utime - this->lastUserCPU); + cpu_percent /= (now - this->lastCPU); + cpu_percent /= this->numProcessors; + cpu_percent *= 100.; + } + this->lastCPU = now; + this->lastSysCPU = timeSample.tms_stime; + this->lastUserCPU = timeSample.tms_utime; + this->cpu_percents.push_back(cpu_percent); + double avg_cpu_usage = std::accumulate(this->cpu_percents.begin(), this->cpu_percents.end(), 0.0) / this->cpu_percents.size(); + + // Print to terminal + printf("\033[2J\033[1;1H"); + + std::cout << std::endl << "==== TRLO v" << this->version_ << " ====" << std::endl; + + if (!this->cpu_type.empty()) { + std::cout << std::endl << this->cpu_type << " x " << this->numProcessors << std::endl; + } + + std::cout << std::endl << std::setprecision(4) << std::fixed; + std::cout << "Position [xyz] :: " << this->pose[0] << " " << this->pose[1] << " " << this->pose[2] << std::endl; + std::cout << "Orientation [wxyz] :: " << this->rotq.w() << " " << this->rotq.x() << " " << this->rotq.y() << " " << this->rotq.z() << std::endl; + std::cout << "Distance Traveled :: " << length_traversed << " meters" << std::endl; + std::cout << "Distance to Origin :: " << sqrt(pow(this->pose[0]-this->origin[0],2) + pow(this->pose[1]-this->origin[1],2) + pow(this->pose[2]-this->origin[2],2)) << " meters" << std::endl; + + std::cout << std::endl << std::right << std::setprecision(2) << std::fixed; + std::cout << "Computation Time :: " << std::setfill(' ') << std::setw(6) << this->comp_times.back()*1000. << " ms // Avg: " << std::setw(5) << avg_comp_time*1000. << std::endl; + std::cout << "Cores Utilized :: " << std::setfill(' ') << std::setw(6) << (cpu_percent/100.) * this->numProcessors << " cores // Avg: " << std::setw(5) << (avg_cpu_usage/100.) * this->numProcessors << std::endl; + std::cout << "CPU Load :: " << std::setfill(' ') << std::setw(6) << cpu_percent << " % // Avg: " << std::setw(5) << avg_cpu_usage << std::endl; + std::cout << "RAM Allocation :: " << std::setfill(' ') << std::setw(6) << resident_set/1000. << " MB // VSZ: " << vm_usage/1000. << " MB" << std::endl; + + std::cout << "Submap build Time :: " << std::setfill(' ') << std::setw(6) << this->submap_build_times.back()*1000. << " ms // Avg: " << std::setw(5) << avg_submap_build_time*1000. << std::endl; + std::cout << "Ground optimize Time :: " << std::setfill(' ') << std::setw(6) << this->ground_optimize_times.back()*1000. << " ms // Avg: " << std::setw(5) << avg_ground_optimize_time*1000. << std::endl; + + std::cout << "concave size is: " << this->keyframe_concave.size() << std::endl; + std::cout << "this->submap_kf_idx_hash size is: " << this->submap_kf_idx_hash.size() << std::endl; +} + + + + + + + + + + + + + + + + + + + + + + + diff --git a/trlo/src/trlo/odom_node.cc b/trlo/src/trlo/odom_node.cc new file mode 100644 index 0000000..5307d1e --- /dev/null +++ b/trlo/src/trlo/odom_node.cc @@ -0,0 +1,34 @@ +/**************************************************************************************** + * + * Copyright (c) 2024, Shenyang Institute of Automation, Chinese Academy of Sciences + * + * Authors: Yanpeng Jia + * Contact: jiayanpeng@sia.cn + * + ****************************************************************************************/ + +#include "trlo/odom.h" + +void controlC(int sig) { + + trlo::OdomNode::abort(); + +} + +int main(int argc, char** argv) { + + ros::init(argc, argv, "trlo_odom_node"); + ros::NodeHandle nh("~"); + + signal(SIGTERM, controlC); + sleep(0.5); + + trlo::OdomNode node(nh); + ros::AsyncSpinner spinner(0); + spinner.start(); + node.start(); + ros::waitForShutdown(); + + return 0; + +} diff --git a/trlo/srv/save_pcd.srv b/trlo/srv/save_pcd.srv new file mode 100644 index 0000000..4692476 --- /dev/null +++ b/trlo/srv/save_pcd.srv @@ -0,0 +1,4 @@ +float32 leaf_size +string save_path +--- +bool success \ No newline at end of file diff --git a/trlo/srv/save_traj.srv b/trlo/srv/save_traj.srv new file mode 100644 index 0000000..939aa5b --- /dev/null +++ b/trlo/srv/save_traj.srv @@ -0,0 +1,3 @@ +string save_path +--- +bool success