Skip to content

Commit fc9db66

Browse files
committedMay 2, 2024
feat: add support of dynamic shape inference
Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
1 parent b959b8c commit fc9db66

File tree

7 files changed

+426
-276
lines changed

7 files changed

+426
-276
lines changed
 
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,18 @@
11
/**:
22
ros__parameters:
3-
model_path: "$(var data_path)/mtr_static.onnx"
4-
precision: "fp32"
5-
target_labels: ["VEHICLE", "PEDESTRIAN", "CYCLIST"]
6-
num_past: 11
7-
num_mode: 6
8-
num_future: 80
9-
max_num_polyline: 768
10-
max_num_point: 20
11-
point_break_distance: 1.0
12-
intention_point_filepath: "$(var data_path)/intention_point.csv"
13-
num_intention_point_cluster: 64
14-
polyline_label_path: "$(var data_path)/polyline_label.txt"
3+
model_params:
4+
model_path: "$(var data_path)/mtr_static.onnx"
5+
target_labels: ["VEHICLE", "PEDESTRIAN", "CYCLIST"]
6+
num_past: 11
7+
num_mode: 6
8+
num_future: 80
9+
max_num_polyline: 768
10+
max_num_point: 20
11+
point_break_distance: 1.0
12+
intention_point_filepath: "$(var data_path)/intention_point.csv"
13+
num_intention_point_cluster: 64
14+
polyline_label_path: "$(var data_path)/polyline_label.txt"
15+
build_params:
16+
is_dynamic: false
17+
precision: "FP32"
18+
calibration: "MINMAX"

‎perception/tensorrt_mtr/include/tensorrt_mtr/builder.hpp

+70-59
Original file line numberDiff line numberDiff line change
@@ -50,77 +50,84 @@ struct TrtDeleter
5050

5151
template <typename T>
5252
using TrtUniquePtr = std::unique_ptr<T, TrtDeleter<T>>;
53-
using BatchConfig = std::array<int32_t, 3>;
5453

55-
struct BuildConfig
56-
{
57-
// type for calibration
58-
std::string calib_type_str;
54+
// Type names of precisions.
55+
enum PrecisionType { FP32 = 0, FP16 = 1, INT8 = 2 };
5956

60-
// DLA core ID that the process uses
61-
int dla_core_id;
57+
// Type names of calibrations.
58+
enum CalibrationType { ENTROPY = 0, LEGACY = 1, PERCENTILE = 2, MINMAX = 3 };
6259

63-
// flag for partial quantization in first layer
64-
bool quantize_first_layer; // For partial quantization
60+
struct BatchOptConfig
61+
{
62+
/**
63+
* @brief Construct a new OptimizationConfig for a static shape inference.
64+
*
65+
* @param value
66+
*/
67+
explicit BatchOptConfig(const int32_t value) : k_min(value), k_opt(value), k_max(value) {}
68+
69+
/**
70+
* @brief Construct a new OptimizationConfig for a dynamic shape inference.
71+
*
72+
* @param k_min
73+
* @param k_opt
74+
* @param k_max
75+
*/
76+
BatchOptConfig(const int32_t k_min, const int32_t k_opt, const int32_t k_max)
77+
: k_min(k_min), k_opt(k_opt), k_max(k_max)
78+
{
79+
}
6580

66-
// flag for partial quantization in last layer
67-
bool quantize_last_layer; // For partial quantization
81+
int32_t k_min, k_opt, k_max;
82+
}; // struct BatchOptConfig
6883

69-
// flag for per-layer profiler using IProfiler
70-
bool profile_per_layer;
84+
struct BuildConfig
85+
{
86+
// type of precision
87+
PrecisionType precision;
7188

72-
// clip value for implicit quantization
73-
double clip_value; // For implicit quantization
89+
// type for calibration
90+
CalibrationType calibration;
7491

75-
// Supported calibration type
76-
const std::array<std::string, 4> valid_calib_type = {"Entropy", "Legacy", "Percentile", "MinMax"};
92+
BatchOptConfig batch_target;
93+
BatchOptConfig batch_agent;
7794

7895
/**
7996
* @brief Construct a new instance with default configurations.
80-
*
8197
*/
8298
BuildConfig()
83-
: calib_type_str("MinMax"),
84-
dla_core_id(-1),
85-
quantize_first_layer(false),
86-
quantize_last_layer(false),
87-
profile_per_layer(false),
88-
clip_value(0.0)
99+
: precision(PrecisionType::FP32),
100+
calibration(CalibrationType::MINMAX),
101+
batch_target(1, 10, 20),
102+
batch_agent(1, 30, 50),
103+
is_dynamic_(false)
89104
{
90105
}
91106

92107
/**
93-
* @brief Construct a new instance with custom configurations.
108+
* @brief Construct a new build config.
94109
*
95-
* @param calib_type_str The name of calibration type which must be selected from [Entropy,
96-
* MinMax].
97-
* @param dla_core_id DLA core ID used by the process.
98-
* @param quantize_first_layer The flag whether to quantize first layer.
99-
* @param quantize_last_layer The flag whether to quantize last layer.
100-
* @param profile_per_layer The flag to profile per-layer in IProfiler.
101-
* @param clip_value The value to be clipped in quantization implicitly.
110+
* @param is_dynamic
111+
* @param precision
112+
* @param calibration
102113
*/
103-
explicit BuildConfig(
104-
const std::string & calib_type_str, const int dla_core_id = -1,
105-
const bool quantize_first_layer = false, const bool quantize_last_layer = false,
106-
const bool profile_per_layer = false, const double clip_value = 0.0)
107-
: calib_type_str(calib_type_str),
108-
dla_core_id(dla_core_id),
109-
quantize_first_layer(quantize_first_layer),
110-
quantize_last_layer(quantize_last_layer),
111-
profile_per_layer(profile_per_layer),
112-
clip_value(clip_value)
114+
BuildConfig(
115+
const bool is_dynamic, const PrecisionType & precision = PrecisionType::FP32,
116+
const CalibrationType & calibration = CalibrationType::MINMAX,
117+
const BatchOptConfig & batch_target = BatchOptConfig(1, 10, 20),
118+
const BatchOptConfig & batch_agent = BatchOptConfig(1, 30, 50))
119+
: precision(precision),
120+
calibration(calibration),
121+
batch_target(batch_target),
122+
batch_agent(batch_agent),
123+
is_dynamic_(is_dynamic)
113124
{
114-
if (
115-
std::find(valid_calib_type.begin(), valid_calib_type.end(), calib_type_str) ==
116-
valid_calib_type.end()) {
117-
std::stringstream message;
118-
message << "Invalid calibration type was specified: " << calib_type_str << std::endl
119-
<< "Valid value is one of: [Entropy, (Legacy | Percentile), MinMax]" << std::endl
120-
<< "Default calibration type will be used: MinMax" << std::endl;
121-
std::cerr << message.str();
122-
}
123125
}
126+
127+
bool is_dynamic() const { return is_dynamic_; }
128+
129+
private:
130+
bool is_dynamic_;
124131
}; // struct BuildConfig
125132

126133
class MTRBuilder
@@ -130,15 +137,12 @@ class MTRBuilder
130137
* @brief Construct a new instance.
131138
*
132139
* @param model_path Path to engine or onnx file.
133-
* @param precision The name of precision type.
134-
* @param batch_config The configuration of min/opt/max batch.
135-
* @param max_workspace_size The max workspace size.
136140
* @param build_config The configuration of build.
141+
* @param max_workspace_size The max workspace size.
137142
*/
138143
MTRBuilder(
139-
const std::string & model_path, const std::string & precision,
140-
const BatchConfig & batch_config = {1, 1, 1}, const size_t max_workspace_size = (1ULL << 30),
141-
const BuildConfig & build_config = BuildConfig());
144+
const std::string & model_path, const BuildConfig & build_config = BuildConfig(),
145+
const size_t max_workspace_size = (1ULL << 63));
142146

143147
/**
144148
* @brief Destroy the instance.
@@ -158,6 +162,12 @@ class MTRBuilder
158162
*/
159163
bool isInitialized() const;
160164

165+
// Return true if the model supports dynamic shape inference.
166+
bool isDynamic() const;
167+
168+
// Set binding dimensions for specified for dynamic shape inference.
169+
bool setBindingDimensions(int index, nvinfer1::Dims dimensions);
170+
161171
/**
162172
* @brief A wrapper of `nvinfer1::IExecuteContext::enqueueV2`.
163173
*
@@ -178,6 +188,9 @@ class MTRBuilder
178188
*/
179189
bool loadEngine(const std::string & filepath);
180190

191+
// Create a cache path of engine file.
192+
fs::path createEngineCachePath() const;
193+
181194
/**
182195
* @brief Build engine from onnx file.
183196
*
@@ -194,8 +207,6 @@ class MTRBuilder
194207
TrtUniquePtr<nvinfer1::IExecutionContext> context_;
195208

196209
fs::path model_filepath_;
197-
std::string precision_;
198-
BatchConfig batch_config_;
199210
size_t max_workspace_size_;
200211
std::unique_ptr<const BuildConfig> build_config_;
201212

‎perception/tensorrt_mtr/include/tensorrt_mtr/node.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ class PolylineTypeMap
7373
public:
7474
explicit PolylineTypeMap(rclcpp::Node * node)
7575
{
76-
const auto filepath = node->declare_parameter<std::string>("polyline_label_path");
76+
const auto filepath = node->declare_parameter<std::string>("model_params.polyline_label_path");
7777
std::ifstream file(filepath);
7878
if (!file.is_open()) {
7979
RCLCPP_ERROR_STREAM(node->get_logger(), "Could not open polyline label file: " << filepath);
@@ -164,6 +164,7 @@ class MTRNode : public rclcpp::Node
164164

165165
// MTR parameters
166166
std::unique_ptr<MTRConfig> config_ptr_;
167+
std::unique_ptr<BuildConfig> build_config_ptr_;
167168
std::unique_ptr<TrtMTR> model_ptr_;
168169
PolylineTypeMap polyline_type_map_;
169170
std::shared_ptr<PolylineData> polyline_ptr_;

‎perception/tensorrt_mtr/include/tensorrt_mtr/trt_mtr.hpp

+11-13
Original file line numberDiff line numberDiff line change
@@ -92,17 +92,15 @@ class TrtMTR
9292
* @brief Construct a new instance.
9393
*
9494
* @param model_path The path to engine or onnx file.
95-
* @param precision The precision type.
9695
* @param config The configuration of model.
97-
* @param batch_config The configuration of batch.
96+
* @param build_config The configuration of build.
9897
* @param max_workspace_size The max size of workspace.
9998
* @param build_config The configuration of build.
10099
*/
101100
TrtMTR(
102-
const std::string & model_path, const std::string & precision,
103-
const MTRConfig & config = MTRConfig(), const BatchConfig & batch_config = {1, 1, 1},
104-
const size_t max_workspace_size = (1ULL << 30),
105-
const BuildConfig & build_config = BuildConfig());
101+
const std::string & model_path, const MTRConfig & config = MTRConfig(),
102+
const BuildConfig & build_config = BuildConfig(),
103+
const size_t max_workspace_size = (1ULL << 30));
106104

107105
/**
108106
* @brief Execute inference.
@@ -160,20 +158,18 @@ class TrtMTR
160158

161159
// data size
162160
// load from input data
163-
size_t num_target_, num_agent_, time_length_;
164-
size_t agent_input_dim_;
165-
size_t num_polyline_, num_point_;
166-
size_t polyline_input_dim_;
161+
int32_t num_target_, num_agent_, num_timestamp_, num_agent_attr_;
162+
int32_t num_polyline_, num_point_, num_point_dim_, num_point_attr_;
167163
// load from config
168-
size_t max_num_polyline_, num_mode_, num_future_;
164+
int32_t max_num_polyline_, num_mode_, num_future_, num_intention_point_;
169165

170166
// source data
171167
cuda::unique_ptr<int[]> d_target_index_{nullptr};
172168
cuda::unique_ptr<int[]> d_label_index_{nullptr};
173-
cuda::unique_ptr<float[]> d_timestamps_{nullptr};
169+
cuda::unique_ptr<float[]> d_timestamp_{nullptr};
174170
cuda::unique_ptr<float[]> d_trajectory_{nullptr};
175171
cuda::unique_ptr<float[]> d_target_state_{nullptr};
176-
cuda::unique_ptr<float[]> d_intention_points_{nullptr};
172+
cuda::unique_ptr<float[]> d_intention_point_{nullptr};
177173
cuda::unique_ptr<float[]> d_polyline_{nullptr};
178174

179175
// preprocessed inputs
@@ -191,6 +187,8 @@ class TrtMTR
191187
// outputs
192188
cuda::unique_ptr<float[]> d_out_score_{nullptr};
193189
cuda::unique_ptr<float[]> d_out_trajectory_{nullptr};
190+
std::unique_ptr<float[]> h_out_score_{nullptr};
191+
std::unique_ptr<float[]> h_out_trajectory_{nullptr};
194192
}; // class TrtMTR
195193
} // namespace trt_mtr
196194
#endif // TENSORRT_MTR__TRT_MTR_HPP_

0 commit comments

Comments
 (0)