Skip to content

Commit 303b0b3

Browse files
committed
passing tests
1 parent 31dc8f9 commit 303b0b3

File tree

4 files changed

+37
-34
lines changed

4 files changed

+37
-34
lines changed

deep_ort_backend_plugin/src/ort_backend_executor.cpp

Lines changed: 16 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ deep_ros::Tensor OrtBackendExecutor::run_inference_impl(deep_ros::Tensor & input
8383
auto * custom_allocator = static_cast<OrtCpuMemoryAllocator *>(custom_allocator_shared.get());
8484

8585
// Create input tensor that wraps existing input memory (zero-copy!)
86-
size_t input_size_bytes = input.size() * get_element_size(input.dtype());
86+
size_t input_size_bytes = input.byte_size();
8787
Ort::Value ort_input = Ort::Value::CreateTensor(
8888
memory_info_, input.data(), input_size_bytes, input_shape_int64.data(), input_shape_int64.size(), onnx_type);
8989

@@ -136,12 +136,26 @@ ONNXTensorElementDataType OrtBackendExecutor::convert_to_onnx_type(deep_ros::Dat
136136
switch (dtype) {
137137
case deep_ros::DataType::FLOAT32:
138138
return ONNX_TENSOR_ELEMENT_DATA_TYPE_FLOAT;
139+
case deep_ros::DataType::FLOAT64:
140+
return ONNX_TENSOR_ELEMENT_DATA_TYPE_DOUBLE;
141+
case deep_ros::DataType::INT8:
142+
return ONNX_TENSOR_ELEMENT_DATA_TYPE_INT8;
143+
case deep_ros::DataType::INT16:
144+
return ONNX_TENSOR_ELEMENT_DATA_TYPE_INT16;
139145
case deep_ros::DataType::INT32:
140146
return ONNX_TENSOR_ELEMENT_DATA_TYPE_INT32;
141147
case deep_ros::DataType::INT64:
142148
return ONNX_TENSOR_ELEMENT_DATA_TYPE_INT64;
143149
case deep_ros::DataType::UINT8:
144150
return ONNX_TENSOR_ELEMENT_DATA_TYPE_UINT8;
151+
case deep_ros::DataType::UINT16:
152+
return ONNX_TENSOR_ELEMENT_DATA_TYPE_UINT16;
153+
case deep_ros::DataType::UINT32:
154+
return ONNX_TENSOR_ELEMENT_DATA_TYPE_UINT32;
155+
case deep_ros::DataType::UINT64:
156+
return ONNX_TENSOR_ELEMENT_DATA_TYPE_UINT64;
157+
case deep_ros::DataType::BOOL:
158+
return ONNX_TENSOR_ELEMENT_DATA_TYPE_BOOL;
145159
default:
146160
throw std::runtime_error("Unsupported data type for ONNX Runtime");
147161
}
@@ -190,18 +204,7 @@ std::vector<size_t> OrtBackendExecutor::get_output_shape(const std::vector<size_
190204

191205
size_t OrtBackendExecutor::get_element_size(deep_ros::DataType dtype) const
192206
{
193-
switch (dtype) {
194-
case deep_ros::DataType::FLOAT32:
195-
return sizeof(float);
196-
case deep_ros::DataType::INT32:
197-
return sizeof(int32_t);
198-
case deep_ros::DataType::INT64:
199-
return sizeof(int64_t);
200-
case deep_ros::DataType::UINT8:
201-
return sizeof(uint8_t);
202-
default:
203-
throw std::runtime_error("Unsupported data type");
204-
}
207+
return deep_ros::get_dtype_size(dtype);
205208
}
206209

207210
} // namespace deep_ort_backend

deep_test/src/mock_plugin/mock_plugin.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -97,10 +97,10 @@ class MockInferenceExecutor : public BackendInferenceExecutor
9797
return true;
9898
}
9999

100-
Tensor run_inference_impl(const Tensor & input) override
100+
Tensor run_inference_impl(Tensor & input) override
101101
{
102-
// For testing, just return a copy of the input tensor
103-
return input;
102+
// For testing, create a simple output tensor with same shape/dtype using input's allocator
103+
return Tensor(input.shape(), input.dtype(), input.allocator());
104104
}
105105

106106
void unload_model_impl() override

deep_test/test/deep_core/test_integration.cpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ TEST_CASE_METHOD(
6161
}
6262

6363
// Run inference
64-
auto output = node->run_inference(std::move(input));
64+
auto output = node->run_inference(input);
6565

6666
// Verify output
6767
REQUIRE(output.data() != nullptr);
@@ -88,7 +88,7 @@ TEST_CASE_METHOD(
8888
data[j] = static_cast<float>(i * 100 + j);
8989
}
9090

91-
auto output = node->run_inference(std::move(input));
91+
auto output = node->run_inference(input);
9292
REQUIRE(output.size() == shape[0] * shape[1] * shape[2] * shape[3]);
9393
}
9494
}
@@ -108,7 +108,7 @@ TEST_CASE_METHOD(
108108
std::vector<size_t> shape = {2, 3};
109109
deep_ros::Tensor input(shape, dtype, allocator);
110110

111-
auto output = node->run_inference(std::move(input));
111+
auto output = node->run_inference(input);
112112
REQUIRE(output.dtype() == dtype);
113113
REQUIRE(output.shape() == shape);
114114
}
@@ -146,7 +146,7 @@ TEST_CASE_METHOD(
146146
// Test inference with first model
147147
auto allocator = node->get_current_allocator();
148148
deep_ros::Tensor input1({2, 2}, deep_ros::DataType::FLOAT32, allocator);
149-
auto output1 = node->run_inference(std::move(input1));
149+
auto output1 = node->run_inference(input1);
150150
REQUIRE(output1.size() == 4);
151151

152152
// Switch to second model
@@ -157,7 +157,7 @@ TEST_CASE_METHOD(
157157

158158
// Test inference with second model
159159
deep_ros::Tensor input2({3, 3}, deep_ros::DataType::FLOAT32, allocator);
160-
auto output2 = node->run_inference(std::move(input2));
160+
auto output2 = node->run_inference(input2);
161161
REQUIRE(output2.size() == 9);
162162
}
163163

@@ -176,7 +176,7 @@ TEST_CASE_METHOD(
176176
for (int i = 0; i < 3; ++i) {
177177
// Run inference
178178
deep_ros::Tensor input({1, 3}, deep_ros::DataType::FLOAT32, allocator);
179-
auto output = node->run_inference(std::move(input));
179+
auto output = node->run_inference(input);
180180
REQUIRE(output.size() == 3);
181181

182182
// Change configuration
@@ -219,7 +219,7 @@ TEST_CASE_METHOD(
219219
// Inference should work
220220
auto allocator = node->get_current_allocator();
221221
deep_ros::Tensor input({2, 2}, deep_ros::DataType::FLOAT32, allocator);
222-
REQUIRE_NOTHROW(node->run_inference(std::move(input)));
222+
REQUIRE_NOTHROW(node->run_inference(input));
223223
}
224224

225225
SECTION("Graceful handling of inference errors")
@@ -235,15 +235,15 @@ TEST_CASE_METHOD(
235235

236236
// Valid inference should work
237237
deep_ros::Tensor valid_input({2, 2}, deep_ros::DataType::FLOAT32, allocator);
238-
REQUIRE_NOTHROW(node->run_inference(std::move(valid_input)));
238+
REQUIRE_NOTHROW(node->run_inference(valid_input));
239239

240240
// Invalid inference should fail gracefully
241241
deep_ros::Tensor invalid_input; // Empty tensor
242-
REQUIRE_THROWS(node->run_inference(std::move(invalid_input)));
242+
REQUIRE_THROWS(node->run_inference(invalid_input));
243243

244244
// Node should still work after error
245245
deep_ros::Tensor recovery_input({3, 3}, deep_ros::DataType::FLOAT32, allocator);
246-
REQUIRE_NOTHROW(node->run_inference(std::move(recovery_input)));
246+
REQUIRE_NOTHROW(node->run_inference(recovery_input));
247247
}
248248

249249
SECTION("Lifecycle error recovery")
@@ -360,7 +360,7 @@ TEST_CASE_METHOD(deep_ros::test::TestExecutorFixture, "Integration: Resource Man
360360
}
361361

362362
// Process
363-
auto output = node->run_inference(std::move(input));
363+
auto output = node->run_inference(input);
364364

365365
// Tensors should be automatically cleaned up
366366
REQUIRE(output.data() != nullptr);

deep_test/test/deep_core/test_plugin_system.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -243,12 +243,12 @@ TEST_CASE_METHOD(
243243
{
244244
// Inference without model should fail
245245
deep_ros::Tensor input({2, 2}, deep_ros::DataType::FLOAT32, allocator);
246-
REQUIRE_THROWS_AS(executor->run_inference(std::move(input)), std::runtime_error);
246+
REQUIRE_THROWS_AS(executor->run_inference(input), std::runtime_error);
247247

248248
// After loading model, inference should work
249249
executor->load_model("/test/model.onnx");
250250
deep_ros::Tensor input2({2, 2}, deep_ros::DataType::FLOAT32, allocator);
251-
REQUIRE_NOTHROW(executor->run_inference(std::move(input2)));
251+
REQUIRE_NOTHROW(executor->run_inference(input2));
252252
}
253253

254254
SECTION("Inference with valid input produces valid output")
@@ -266,7 +266,7 @@ TEST_CASE_METHOD(
266266
}
267267

268268
// Run inference
269-
auto output = executor->run_inference(std::move(input));
269+
auto output = executor->run_inference(input);
270270

271271
// Output should be valid tensor
272272
REQUIRE(output.data() != nullptr);
@@ -285,7 +285,7 @@ TEST_CASE_METHOD(
285285

286286
// Inference after unload should fail
287287
deep_ros::Tensor input({1, 1}, deep_ros::DataType::FLOAT32, allocator);
288-
REQUIRE_THROWS_AS(executor->run_inference(std::move(input)), std::runtime_error);
288+
REQUIRE_THROWS_AS(executor->run_inference(input), std::runtime_error);
289289
}
290290
}
291291

@@ -301,7 +301,7 @@ TEST_CASE_METHOD(deep_ros::test::MockBackendFixture, "Plugin System: Error Handl
301301

302302
// Empty tensor should be rejected
303303
deep_ros::Tensor empty_tensor;
304-
REQUIRE_THROWS(executor->run_inference(std::move(empty_tensor)));
304+
REQUIRE_THROWS(executor->run_inference(empty_tensor));
305305
}
306306

307307
SECTION("Memory allocation failures are handled")
@@ -324,7 +324,7 @@ TEST_CASE_METHOD(deep_ros::test::MockBackendFixture, "Plugin System: Error Handl
324324
// Failed operations shouldn't break the plugin
325325
try {
326326
deep_ros::Tensor empty_tensor;
327-
executor->run_inference(std::move(empty_tensor));
327+
executor->run_inference(empty_tensor);
328328
} catch (...) {
329329
// Error is expected
330330
}
@@ -333,6 +333,6 @@ TEST_CASE_METHOD(deep_ros::test::MockBackendFixture, "Plugin System: Error Handl
333333
REQUIRE(executor->load_model("/recovery/model.onnx") == true);
334334

335335
deep_ros::Tensor valid_input({2, 2}, deep_ros::DataType::FLOAT32, allocator);
336-
REQUIRE_NOTHROW(executor->run_inference(std::move(valid_input)));
336+
REQUIRE_NOTHROW(executor->run_inference(valid_input));
337337
}
338338
}

0 commit comments

Comments
 (0)