feat(synthetic): add DisparityComputingMethod

This commit is contained in:
TinyOh
2019-01-23 17:17:08 +08:00
parent 4011880148
commit 0b71d05813
11 changed files with 137 additions and 351 deletions

View File

@@ -20,21 +20,16 @@
#include "mynteye/logger.h"
#define WITH_BM_SOBEL_FILTER
MYNTEYE_BEGIN_NAMESPACE
const char DisparityProcessor::NAME[] = "DisparityProcessor";
DisparityProcessor::DisparityProcessor(DisparityProcessorType type,
DisparityProcessor::DisparityProcessor(DisparityComputingMethod type,
std::int32_t proc_period)
: Processor(std::move(proc_period)), type_(type) {
VLOG(2) << __func__ << ": proc_period=" << proc_period;
if (type_ == DisparityProcessorType::SGBM) {
int sgbmWinSize = 3;
int numberOfDisparities = 64;
int sgbmWinSize = 3;
int numberOfDisparities = 64;
#ifdef WITH_OPENCV2
// StereoSGBM
// http://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html?#stereosgbm
@@ -51,22 +46,6 @@ DisparityProcessor::DisparityProcessor(DisparityProcessorType type,
100, // speckleWindowSize
32, // speckleRange
false)); // fullDP
#else
sgbm_matcher = cv::StereoSGBM::create(0, 16, 3);
sgbm_matcher->setPreFilterCap(63);
sgbm_matcher->setBlockSize(sgbmWinSize);
sgbm_matcher->setP1(8 * sgbmWinSize * sgbmWinSize);
sgbm_matcher->setP2(32 * sgbmWinSize * sgbmWinSize);
sgbm_matcher->setMinDisparity(0);
sgbm_matcher->setNumDisparities(numberOfDisparities);
sgbm_matcher->setUniquenessRatio(10);
sgbm_matcher->setSpeckleWindowSize(100);
sgbm_matcher->setSpeckleRange(32);
sgbm_matcher->setDisp12MaxDiff(1);
#endif
#ifdef WITH_BM_SOBEL_FILTER
} else if (type_ == DisparityProcessorType::BM) {
#ifdef WITH_OPENCV2
LOG(ERROR) << "not supported in opencv 2.x";
// int bmWinSize = 3;
// // StereoBM
@@ -83,6 +62,18 @@ DisparityProcessor::DisparityProcessor(DisparityProcessorType type,
// 100,
// 4));
#else
sgbm_matcher = cv::StereoSGBM::create(0, 16, 3);
sgbm_matcher->setPreFilterCap(63);
sgbm_matcher->setBlockSize(sgbmWinSize);
sgbm_matcher->setP1(8 * sgbmWinSize * sgbmWinSize);
sgbm_matcher->setP2(32 * sgbmWinSize * sgbmWinSize);
sgbm_matcher->setMinDisparity(0);
sgbm_matcher->setNumDisparities(numberOfDisparities);
sgbm_matcher->setUniquenessRatio(10);
sgbm_matcher->setSpeckleWindowSize(100);
sgbm_matcher->setSpeckleRange(32);
sgbm_matcher->setDisp12MaxDiff(1);
bm_matcher = cv::StereoBM::create(0, 3);
bm_matcher->setPreFilterSize(9);
bm_matcher->setPreFilterCap(31);
@@ -95,48 +86,23 @@ DisparityProcessor::DisparityProcessor(DisparityProcessorType type,
bm_matcher->setSpeckleRange(4);
bm_matcher->setPreFilterType(cv::StereoBM::PREFILTER_XSOBEL);
#endif
#endif
} else {
LOG(ERROR) << "no enum DisparityProcessorType,use default sgbm";
int sgbmWinSize = 3;
int numberOfDisparities = 64;
NotifyComputingTypeChanged(type_);
}
#ifdef WITH_OPENCV2
// StereoSGBM
// http://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html?#stereosgbm
sgbm_matcher = cv::Ptr<cv::StereoSGBM>(
new cv::StereoSGBM(
0, // minDisparity
numberOfDisparities, // numDisparities
sgbmWinSize, // SADWindowSize
8 * sgbmWinSize * sgbmWinSize, // P1
32 * sgbmWinSize * sgbmWinSize, // P2
1, // disp12MaxDiff
63, // preFilterCap
10, // uniquenessRatio
100, // speckleWindowSize
32, // speckleRange
false)); // fullDP
#else
sgbm_matcher = cv::StereoSGBM::create(0, 16, 3);
sgbm_matcher->setPreFilterCap(63);
sgbm_matcher->setBlockSize(sgbmWinSize);
sgbm_matcher->setP1(8 * sgbmWinSize * sgbmWinSize);
sgbm_matcher->setP2(32 * sgbmWinSize * sgbmWinSize);
sgbm_matcher->setMinDisparity(0);
sgbm_matcher->setNumDisparities(numberOfDisparities);
sgbm_matcher->setUniquenessRatio(10);
sgbm_matcher->setSpeckleWindowSize(100);
sgbm_matcher->setSpeckleRange(32);
sgbm_matcher->setDisp12MaxDiff(1);
#endif
}
void DisparityProcessor::NotifyComputingTypeChanged(
const DisparityComputingMethod &MethodType) {
type_ = MethodType;
}
DisparityProcessor::~DisparityProcessor() {
VLOG(2) << __func__;
}
void DisparityProcessor::SetDisparityComputingMethodType(
const DisparityComputingMethod &MethodType) {
NotifyComputingTypeChanged(MethodType);
}
std::string DisparityProcessor::Name() {
return NAME;
}
@@ -161,16 +127,14 @@ bool DisparityProcessor::OnProcess(
// It contains disparity values scaled by 16. So, to get the floating-point
// disparity map,
// you need to divide each disp element by 16.
if (type_ == DisparityProcessorType::SGBM) {
if (type_ == DisparityComputingMethod::SGBM) {
(*sgbm_matcher)(input->first, input->second, disparity);
#ifdef WITH_BM_SOBEL_FILTER
} else if (type_ == DisparityProcessorType::BM) {
} else if (type_ == DisparityComputingMethod::BM) {
LOG(ERROR) << "not supported in opencv 2.x";
// cv::Mat tmp1, tmp2;
// cv::cvtColor(input->first, tmp1, CV_RGB2GRAY);
// cv::cvtColor(input->second, tmp2, CV_RGB2GRAY);
// (*bm_matcher)(tmp1, tmp2, disparity);
#endif
}
#else
// compute()
@@ -180,10 +144,9 @@ bool DisparityProcessor::OnProcess(
// disparity map
// (where each disparity value has 4 fractional bits),
// whereas other algorithms output 32-bit floating-point disparity map.
if (type_ == DisparityProcessorType::SGBM) {
if (type_ == DisparityComputingMethod::SGBM) {
sgbm_matcher->compute(input->first, input->second, disparity);
#ifdef WITH_BM_SOBEL_FILTER
} else if (type_ == DisparityProcessorType::BM) {
} else if (type_ == DisparityComputingMethod::BM) {
cv::Mat tmp1, tmp2;
if (input->first.channels() == 1) {
// s1030
@@ -195,7 +158,6 @@ bool DisparityProcessor::OnProcess(
cv::cvtColor(input->second, tmp2, CV_RGB2GRAY);
}
bm_matcher->compute(tmp1, tmp2, disparity);
#endif
} else {
// default
sgbm_matcher->compute(input->first, input->second, disparity);

View File

@@ -17,6 +17,7 @@
#include <string>
#include "mynteye/api/processor.h"
#include "mynteye/types.h"
namespace cv {
@@ -24,27 +25,20 @@ class StereoSGBM;
class StereoBM;
} // namespace cv
enum class DisparityProcessorType : std::uint8_t {
/** bm */
SGBM = 0,
/** sgbm */
BM = 1,
/** unknow */
UNKNOW
};
MYNTEYE_BEGIN_NAMESPACE
class DisparityProcessor : public Processor {
public:
static const char NAME[];
explicit DisparityProcessor(DisparityProcessorType type,
explicit DisparityProcessor(DisparityComputingMethod type,
std::int32_t proc_period = 0);
virtual ~DisparityProcessor();
std::string Name() override;
void SetDisparityComputingMethodType(
const DisparityComputingMethod &MethodType);
void NotifyComputingTypeChanged(const DisparityComputingMethod &MethodType);
protected:
Object *OnCreateOutput() override;
@@ -55,7 +49,7 @@ class DisparityProcessor : public Processor {
private:
cv::Ptr<cv::StereoSGBM> sgbm_matcher;
cv::Ptr<cv::StereoBM> bm_matcher;
DisparityProcessorType type_;
DisparityComputingMethod type_;
};
MYNTEYE_END_NAMESPACE

View File

@@ -22,9 +22,7 @@ MYNTEYE_BEGIN_NAMESPACE
const char RootProcessor::NAME[] = "RootProcessor";
RootProcessor::RootProcessor(std::int32_t proc_period)
: Processor(std::move(proc_period)) {
// todo
}
: Processor(std::move(proc_period)) {}
RootProcessor::~RootProcessor() {
VLOG(2) << __func__;
}
@@ -40,14 +38,6 @@ bool RootProcessor::OnProcess(
Object *const in, Object *const out,
std::shared_ptr<Processor> const parent) {
MYNTEYE_UNUSED(parent)
// const ObjMat2 *input = Object::Cast<ObjMat2>(in);
// ObjMat2 *output = Object::Cast<ObjMat2>(out);
// cv::remap(input->first, output->first, map11, map12, cv::INTER_LINEAR);
// cv::remap(input->second, output->second, map21, map22, cv::INTER_LINEAR);
// output->first_id = input->first_id;
// output->first_data = input->first_data;
// output->second_id = input->second_id;
// output->second_data = input->second_data;
return true;
}
MYNTEYE_END_NAMESPACE