整理资料发现未对Bumblebee的分离图像、保存成cv::Mat格式的使用方法留存笔记,这里补上,备忘。
使用须知
-
下述Bumblebee相机直接获取的图片是左右视图混合(interleaved)之后的结果,如果需要进行双目视觉处理,需要对interleaved的结果进行分离,得到左右相机采集的图片;
-
Bumblebee相机出厂时即被标定好,无需自己标定,使用官方提供的API即可获得标定好的左右视图;当然也可以获得raw图,自己进行标定。
-
标定好的stereo pairs只是进行了相机标定,如果使用该图片计算深度图,还需进行立体校正,使相机满足极线约束。
代码
环境:Win10+OpenCV3.4.1 +(Triclops_4.0.3.4_x64+FlyCapture_2.12.3.31_x64)
/*
可选分辨率:
320×240; 384×288; 400×300; 512×384;
640×480; 768×576; 800×600; 960×720;
1024×768; 1152×864; 1280×960;
*/
#include <iostream>
#include <fstream>
#include <string>
#include "captureimages.h"
#include "Example_Exception.h"
#include <opencv2/highgui.hpp>
#include <opencv2/opencv.hpp>
using namespace std;
using namespace cv;
int feed_height = 480, feed_width = 640; // 设置输出分辨率
int main(int /* argc */, char ** /* argv */)
{
TriclopsError triclops_status;
TriclopsContext context;
TriclopsColorStereoPair colorStereoInput;
// camera to be used to grab color image
FC2::Camera camera;
// grabbed unprocessed image
FC2::Image grabbedImage;
try {
// connect camera
FC2::Error flycap_status = camera.Connect();
handleError("FlyCapture2::Camera::Connect()", flycap_status, __LINE__);
// configure camera by setting stereo mode
//configureCamera(camera);
// 选择使用的相机:左+右 OR 中+右
FC2T::ErrorType fc2TriclopsError;
FC2T::StereoCameraMode mode = FC2T::TWO_CAMERA_WIDE;//TWO_CAMERA_WIDE TWO_CAMERA_NARROW
fc2TriclopsError = FC2T::setStereoMode(camera, mode);
handleError("Fc2Triclops::setStereoMode()", fc2TriclopsError, __LINE__);
// generate the Triclops context
generateTriclopsContext(camera, context);
// 注意:必须先设置triclopsSetCameraConfiguration,再设置分辨率:triclopsPrepareRectificationData,否则会导致同一分辨率下,不同基线对应的焦距不同
// Setting the camera configuration. This is useful only when using a triple sensor stereo camera (e.g. XB3)
triclops_status = triclopsSetCameraConfiguration(context, TriCfg_2CAM_HORIZONTAL_WIDE);// TriCfg_2CAM_HORIZONTAL_WIDE TriCfg_2CAM_HORIZONTAL_NARROW
triclops_examples::handleError("triclopsSetCameraConfiguration()", triclops_status, __LINE__);
// Prepare the rectification buffers using the input resolution as output resolution.
triclops_status = triclopsPrepareRectificationData(context, feed_height, feed_width, feed_height, feed_width);
triclops_examples::handleError("triclopsPrepareRectificationData()", triclops_status, __LINE__);
// 开始采集数据
FC2::Error fc2Error = camera.StartCapture();
handleError("FlyCapture2::Camera::StartCapture()", fc2Error, __LINE__);
while (