Skip to content

Commit a28a347

Browse files
author
Matevz Morato
committed
Merge branch 'colormono_deprecation' into v3_develop
2 parents c499902 + 8ef9e48 commit a28a347

31 files changed

+108
-707
lines changed

bindings/python/src/pipeline/PipelineBindings.cpp

Lines changed: 13 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -177,6 +177,19 @@ void PipelineBindings::bind(pybind11::module& m, void* pCallstack) {
177177
// so we create in the same manner as device nodes.
178178
auto isFromBindings = class_.attr("__module__").cast<std::string>() == "depthai.node";
179179
// Create a copy from kwargs and add autoAddToPipeline to false
180+
181+
// Check if the node is a ColorCamera or a MonoCamera node and issue a deprecation warning
182+
py::object colorCameraClass = py::module::import("depthai").attr("node").attr("ColorCamera");
183+
py::object monoCameraClass = py::module::import("depthai").attr("node").attr("MonoCamera");
184+
if(class_.is(colorCameraClass)){
185+
PyErr_WarnEx(PyExc_DeprecationWarning,
186+
"ColorCamera node is deprecated. Use Camera node instead.", 1);
187+
}
188+
189+
if(class_.is(monoCameraClass)){
190+
PyErr_WarnEx(PyExc_DeprecationWarning,
191+
"MonoCamera node is deprecated. Use Camera node instead.", 1);
192+
}
180193
if(isSubclass && !isFromBindings) {
181194
setImplicitPipeline(&p);
182195
std::shared_ptr<Node> hostNode = py::cast<std::shared_ptr<node::ThreadedHostNode>>(class_(*args, **kwargs));
@@ -204,34 +217,6 @@ void PipelineBindings::bind(pybind11::module& m, void* pCallstack) {
204217
return node;
205218
},
206219
py::keep_alive<1, 0>())
207-
// TODO(themarpe) DEPRECATE, use pipeline.create([class name])
208-
// templated create<NODE> function
209-
.def("createXLinkIn", &Pipeline::create<node::XLinkIn>)
210-
.def("createXLinkOut", &Pipeline::create<node::XLinkOut>)
211-
.def("createNeuralNetwork", &Pipeline::create<node::NeuralNetwork>)
212-
.def("createColorCamera", &Pipeline::create<node::ColorCamera>)
213-
.def("createVideoEncoder", &Pipeline::create<node::VideoEncoder>)
214-
.def("createScript", &Pipeline::create<node::Script>)
215-
.def("createSPIOut", &Pipeline::create<node::SPIOut>)
216-
.def("createSPIIn", &Pipeline::create<node::SPIIn>)
217-
.def("createImageManip", &Pipeline::create<node::ImageManip>)
218-
.def("createMonoCamera", &Pipeline::create<node::MonoCamera>)
219-
.def("createStereoDepth", &Pipeline::create<node::StereoDepth>)
220-
.def("createMobileNetDetectionNetwork", &Pipeline::create<node::MobileNetDetectionNetwork>)
221-
.def("createYoloDetectionNetwork", &Pipeline::create<node::YoloDetectionNetwork>)
222-
.def("createSystemLogger", &Pipeline::create<node::SystemLogger>)
223-
.def("createSpatialLocationCalculator", &Pipeline::create<node::SpatialLocationCalculator>)
224-
.def("createMobileNetSpatialDetectionNetwork", &Pipeline::create<node::MobileNetSpatialDetectionNetwork>)
225-
.def("createYoloSpatialDetectionNetwork", &Pipeline::create<node::YoloSpatialDetectionNetwork>)
226-
.def("createObjectTracker", &Pipeline::create<node::ObjectTracker>)
227-
.def("createIMU", &Pipeline::create<node::IMU>)
228-
.def("createEdgeDetector", &Pipeline::create<node::EdgeDetector>)
229-
.def("createFeatureTracker", &Pipeline::create<node::FeatureTracker>)
230-
.def("createAprilTag", &Pipeline::create<node::AprilTag>)
231-
.def("createDetectionParser", &Pipeline::create<node::DetectionParser>)
232-
.def("createUVC", &Pipeline::create<node::UVC>)
233-
.def("createCamera", &Pipeline::create<node::Camera>)
234-
.def("createWarp", &Pipeline::create<node::Warp>)
235220
.def("start", &Pipeline::start)
236221
.def("wait",
237222
[](Pipeline& p) {

bindings/python/src/pipeline/node/ColorCameraBindings.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
#include "depthai/pipeline/node/ColorCamera.hpp"
66
#include "depthai/utility/CompilerWarnings.hpp"
77

8+
DEPTHAI_BEGIN_SUPPRESS_DEPRECATION_WARNING
89
void bind_colorcamera(pybind11::module& m, void* pCallstack) {
910
using namespace dai;
1011
using namespace dai::node;
@@ -89,7 +90,6 @@ void bind_colorcamera(pybind11::module& m, void* pCallstack) {
8990
.def_readwrite("warpMeshStepWidth", &ColorCameraProperties::warpMeshStepWidth)
9091
.def_readwrite("warpMeshStepHeight", &ColorCameraProperties::warpMeshStepHeight)
9192
.def_readwrite("eventFilter", &ColorCameraProperties::eventFilter);
92-
DEPTHAI_BEGIN_SUPPRESS_DEPRECATION_WARNING
9393
// ColorCamera node
9494
colorCamera
9595
.def(py::init([]() {

bindings/python/src/pipeline/node/MonoCameraBindings.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,11 +3,13 @@
33
#include "depthai/pipeline/Node.hpp"
44
#include "depthai/pipeline/Pipeline.hpp"
55
#include "depthai/pipeline/node/MonoCamera.hpp"
6+
#include "depthai/utility/CompilerWarnings.hpp"
67

78
void bind_monocamera(pybind11::module& m, void* pCallstack) {
89
using namespace dai;
910
using namespace dai::node;
1011

12+
DEPTHAI_BEGIN_SUPPRESS_DEPRECATION_WARNING
1113
// Node and Properties declare upfront
1214
py::class_<MonoCameraProperties> monoCameraProperties(m, "MonoCameraProperties", DOC(dai, MonoCameraProperties));
1315
py::enum_<MonoCameraProperties::SensorResolution> monoCameraPropertiesSensorResolution(
@@ -93,4 +95,5 @@ void bind_monocamera(pybind11::module& m, void* pCallstack) {
9395
.def("setRawOutputPacked", &MonoCamera::setRawOutputPacked, py::arg("packed"), DOC(dai, node, MonoCamera, setRawOutputPacked));
9496
// ALIAS
9597
daiNodeModule.attr("MonoCamera").attr("Properties") = monoCameraProperties;
98+
DEPTHAI_END_SUPPRESS_DEPRECATION_WARNING
9699
}

examples/cpp/CMakeLists.txt

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -306,8 +306,6 @@ dai_set_example_test_labels(stereo ondevice rvc2_all rvc4 ci)
306306
dai_add_example(thermal RVC2/Thermal/thermal.cpp OFF OFF)
307307

308308
# Host nodes
309-
dai_add_example(rgb_video RVC2/ColorCamera/rgb_video.cpp OFF OFF)
310-
dai_add_example(rgb_video_camera RVC2/Camera/rgb_video_camera.cpp OFF OFF)
311309
dai_add_example(host_node HostNodes/host_node.cpp OFF OFF)
312310
dai_add_example(threaded_host_node HostNodes/threaded_host_node.cpp OFF OFF)
313311

examples/cpp/HostNodes/host_node.cpp

Lines changed: 5 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -59,16 +59,13 @@ class StreamMerger : public dai::NodeCRTP<dai::node::HostNode, StreamMerger> {
5959

6060
int main() {
6161
// Create pipeline
62-
dai::Pipeline pipeline(true);
62+
dai::Pipeline pipeline;
6363

64-
auto camRgb = pipeline.create<dai::node::ColorCamera>();
65-
camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A);
66-
camRgb->setVideoSize(640, 480);
64+
auto camRgb = pipeline.create<dai::node::Camera>()->build(dai::CameraBoardSocket::CAM_A);
65+
auto camMono = pipeline.create<dai::node::Camera>()->build(dai::CameraBoardSocket::CAM_B);
6766

68-
auto camMono = pipeline.create<dai::node::MonoCamera>();
69-
camMono->setBoardSocket(dai::CameraBoardSocket::CAM_B);
70-
71-
auto streamMerger = pipeline.create<StreamMerger>()->build(camRgb->video, camMono->out);
67+
auto streamMerger = pipeline.create<StreamMerger>()->build(*camRgb->requestOutput(std::make_pair(640, 480)),
68+
*camMono->requestOutput(std::make_pair(640, 480)));
7269
auto display = pipeline.create<Display>()->build(streamMerger->out);
7370

7471
pipeline.start();

examples/cpp/ImageManip/image_manip_v2_resize.cpp

Lines changed: 3 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -16,24 +16,18 @@ int main(int argc, char** argv) {
1616
}
1717
dai::Pipeline pipeline(device);
1818

19-
auto camRgb = pipeline.create<dai::node::ColorCamera>();
19+
auto camRgb = pipeline.create<dai::node::Camera>()->build(dai::CameraBoardSocket::CAM_A);
2020
auto display = pipeline.create<dai::node::Display>();
2121
auto manip = pipeline.create<dai::node::ImageManipV2>();
2222

23-
camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A);
24-
camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P);
2523

2624
// Resize to 400x400 and avoid stretching by cropping from the center
2725
manip->initialConfig.setOutputSize(400, 400, dai::ImageManipConfigV2::ResizeMode::CENTER_CROP);
2826
// Set output frame type
2927
manip->initialConfig.setFrameType(dai::ImgFrame::Type::RGB888i);
3028

31-
camRgb->video.link(manip->inputImage);
29+
camRgb->requestOutput((std::make_pair(1920, 1080)))->link(manip->inputImage);
3230
manip->out.link(display->input);
3331

34-
pipeline.start();
35-
36-
std::this_thread::sleep_for(std::chrono::seconds(30));
37-
38-
pipeline.stop();
32+
pipeline.run();
3933
}

examples/cpp/RVC2/Camera/rgb_video_camera.cpp

Lines changed: 0 additions & 31 deletions
This file was deleted.

examples/cpp/RVC2/ColorCamera/rgb_video.cpp

Lines changed: 0 additions & 34 deletions
This file was deleted.

examples/cpp/RVC2/ImageAlign/image_align.cpp

Lines changed: 7 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -2,17 +2,11 @@
22
#include <opencv2/opencv.hpp>
33
#include <queue>
44

5+
#include "depthai/common/CameraBoardSocket.hpp"
56
#include "depthai/depthai.hpp"
67

78
constexpr auto FPS = 30.0;
89

9-
constexpr auto RGB_SOCKET = dai::CameraBoardSocket::CAM_A;
10-
constexpr auto LEFT_SOCKET = dai::CameraBoardSocket::CAM_B;
11-
constexpr auto ALIGN_SOCKET = LEFT_SOCKET;
12-
13-
constexpr auto COLOR_RESOLUTION = dai::ColorCameraProperties::SensorResolution::THE_1080_P;
14-
constexpr auto LEFT_RIGHT_RESOLUTION = dai::MonoCameraProperties::SensorResolution::THE_720_P;
15-
1610
class FPSCounter {
1711
public:
1812
void tick() {
@@ -48,26 +42,18 @@ void updateDepthPlane(int depth, void*) {
4842

4943
int main() {
5044
dai::Pipeline pipeline;
51-
auto camRgb = pipeline.create<dai::node::ColorCamera>();
52-
auto left = pipeline.create<dai::node::MonoCamera>();
45+
auto camRgb = pipeline.create<dai::node::Camera>()->build(dai::CameraBoardSocket::CAM_A, std::nullopt, FPS);
46+
auto left = pipeline.create<dai::node::Camera>()->build(dai::CameraBoardSocket::CAM_B, std::nullopt, FPS);
5347
auto sync = pipeline.create<dai::node::Sync>();
5448
auto align = pipeline.create<dai::node::ImageAlign>();
5549

56-
left->setResolution(LEFT_RIGHT_RESOLUTION);
57-
left->setBoardSocket(LEFT_SOCKET);
58-
left->setFps(FPS);
59-
60-
camRgb->setBoardSocket(RGB_SOCKET);
61-
camRgb->setResolution(COLOR_RESOLUTION);
62-
camRgb->setFps(FPS);
63-
camRgb->setIspScale(1, 3);
64-
6550
sync->setSyncThreshold(std::chrono::milliseconds(static_cast<int>((1 / FPS) * 1000.0 * 0.5)));
6651

6752
align->outputAligned.link(sync->inputs["aligned"]);
68-
camRgb->isp.link(sync->inputs["rgb"]);
69-
camRgb->isp.link(align->inputAlignTo);
70-
left->out.link(align->input);
53+
auto* RGBOutput = camRgb->requestOutput(std::make_pair(640, 400));
54+
RGBOutput->link(align->inputAlignTo);
55+
RGBOutput->link(sync->inputs["rgb"]);
56+
left->requestOutput(std::make_pair(640, 400))->link(align->input);
7157
auto queue = sync->out.createOutputQueue();
7258

7359
auto alignQ = align->inputConfig.createInputQueue();

examples/cpp/RVC2/VSLAM/basalt_vio.cpp

Lines changed: 4 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,8 @@ int main() {
1010
int width = 640;
1111
int height = 400;
1212
// Define sources and outputs
13-
auto left = pipeline.create<dai::node::MonoCamera>();
14-
auto right = pipeline.create<dai::node::MonoCamera>();
13+
auto left = pipeline.create<dai::node::Camera>()->build(dai::CameraBoardSocket::CAM_B, std::nullopt, fps);
14+
auto right = pipeline.create<dai::node::Camera>()->build(dai::CameraBoardSocket::CAM_C, std::nullopt, fps);
1515
auto imu = pipeline.create<dai::node::IMU>();
1616
auto odom = pipeline.create<dai::node::BasaltVIO>();
1717

@@ -20,17 +20,9 @@ int main() {
2020
imu->setBatchReportThreshold(1);
2121
imu->setMaxBatchReports(10);
2222

23-
left->setCamera("left");
24-
left->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
25-
left->setFps(fps);
26-
right->setCamera("right");
27-
right->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
28-
right->setFps(fps);
29-
3023
// Linking
31-
32-
left->out.link(odom->left);
33-
right->out.link(odom->right);
24+
left->requestOutput(std::make_pair(width, height))->link(odom->left);
25+
right->requestOutput(std::make_pair(width, height))->link(odom->right);
3426
imu->out.link(odom->imu);
3527
odom->transform.link(rerun->inputTrans);
3628
odom->passthrough.link(rerun->inputImg);

0 commit comments

Comments
 (0)