ImageManip Rotate¶
This example showcases how to rotate color and mono frames with the help of ImageManip node. In the example, we are rotating by 90°.
Note
Due to HW warp constraint, input image (to be rotated) has to have width value of multiples of 16.
Demos¶
Here I have DepthAI device positioned vertically on my desk.
Setup¶
Please run the install script to download all required dependencies. Please note that this script must be ran from git context, so you have to download the depthai-python repository first and then run the script
git clone https://github.com/luxonis/depthai-python.git
cd depthai-python/examples
python3 install_requirements.py
For additional information, please follow installation guide
Source code¶
Also available on GitHub
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 | #!/usr/bin/env python3
import cv2
import depthai as dai
# Create pipeline
pipeline = dai.Pipeline()
# Rotate color frames
camRgb = pipeline.create(dai.node.ColorCamera)
camRgb.setPreviewSize(640, 400)
camRgb.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1080_P)
camRgb.setInterleaved(False)
manipRgb = pipeline.create(dai.node.ImageManip)
rgbRr = dai.RotatedRect()
rgbRr.center.x, rgbRr.center.y = camRgb.getPreviewWidth() // 2, camRgb.getPreviewHeight() // 2
rgbRr.size.width, rgbRr.size.height = camRgb.getPreviewHeight(), camRgb.getPreviewWidth()
rgbRr.angle = 90
manipRgb.initialConfig.setCropRotatedRect(rgbRr, False)
camRgb.preview.link(manipRgb.inputImage)
manipRgbOut = pipeline.create(dai.node.XLinkOut)
manipRgbOut.setStreamName("manip_rgb")
manipRgb.out.link(manipRgbOut.input)
# Rotate mono frames
monoLeft = pipeline.create(dai.node.MonoCamera)
monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
monoLeft.setCamera("left")
manipLeft = pipeline.create(dai.node.ImageManip)
rr = dai.RotatedRect()
rr.center.x, rr.center.y = monoLeft.getResolutionWidth() // 2, monoLeft.getResolutionHeight() // 2
rr.size.width, rr.size.height = monoLeft.getResolutionHeight(), monoLeft.getResolutionWidth()
rr.angle = 90
manipLeft.initialConfig.setCropRotatedRect(rr, False)
monoLeft.out.link(manipLeft.inputImage)
manipLeftOut = pipeline.create(dai.node.XLinkOut)
manipLeftOut.setStreamName("manip_left")
manipLeft.out.link(manipLeftOut.input)
with dai.Device(pipeline) as device:
qLeft = device.getOutputQueue(name="manip_left", maxSize=8, blocking=False)
qRgb = device.getOutputQueue(name="manip_rgb", maxSize=8, blocking=False)
while True:
inLeft = qLeft.tryGet()
if inLeft is not None:
cv2.imshow('Left rotated', inLeft.getCvFrame())
inRgb = qRgb.tryGet()
if inRgb is not None:
cv2.imshow('Color rotated', inRgb.getCvFrame())
if cv2.waitKey(1) == ord('q'):
break
|
Also available on GitHub
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 | #include <iostream>
// Includes common necessary includes for development using depthai library
#include "depthai/depthai.hpp"
int main() {
using namespace std;
// Create pipeline
dai::Pipeline pipeline;
// Rotate color frames
auto camRgb = pipeline.create<dai::node::ColorCamera>();
camRgb->setPreviewSize(640, 400);
camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P);
camRgb->setInterleaved(false);
auto manipRgb = pipeline.create<dai::node::ImageManip>();
dai::RotatedRect rgbRr = {{camRgb->getPreviewWidth() / 2.0f, camRgb->getPreviewHeight() / 2.0f}, // center
{camRgb->getPreviewHeight() * 1.0f, camRgb->getPreviewWidth() * 1.0f}, // size
90}; // angle
manipRgb->initialConfig.setCropRotatedRect(rgbRr, false);
camRgb->preview.link(manipRgb->inputImage);
auto manipRgbOut = pipeline.create<dai::node::XLinkOut>();
manipRgbOut->setStreamName("manip_rgb");
manipRgb->out.link(manipRgbOut->input);
// Rotate mono frames
auto monoLeft = pipeline.create<dai::node::MonoCamera>();
monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
monoLeft->setCamera("left");
auto manipLeft = pipeline.create<dai::node::ImageManip>();
dai::RotatedRect rr = {{monoLeft->getResolutionWidth() / 2.0f, monoLeft->getResolutionHeight() / 2.0f}, // center
{monoLeft->getResolutionHeight() * 1.0f, monoLeft->getResolutionWidth() * 1.0f}, // size
90}; // angle
manipLeft->initialConfig.setCropRotatedRect(rr, false);
monoLeft->out.link(manipLeft->inputImage);
auto manipLeftOut = pipeline.create<dai::node::XLinkOut>();
manipLeftOut->setStreamName("manip_left");
manipLeft->out.link(manipLeftOut->input);
dai::Device device(pipeline);
auto qLeft = device.getOutputQueue("manip_left", 8, false);
auto qRgb = device.getOutputQueue("manip_rgb", 8, false);
while(true) {
auto inLeft = qLeft->tryGet<dai::ImgFrame>();
if(inLeft) {
cv::imshow("Left rotated", inLeft->getCvFrame());
}
auto inRgb = qRgb->tryGet<dai::ImgFrame>();
if(inRgb) {
cv::imshow("Color rotated", inRgb->getCvFrame());
}
int key = cv::waitKey(1);
if(key == 'q' || key == 'Q') return 0;
}
return 0;
}
|