Merge branch 'develop' of http://gitlab.mynt.com/mynteye/mynt-eye-s-sdk into develop

This commit is contained in:
Osenberg 2019-03-27 14:59:37 +08:00
commit 8968f19819
10 changed files with 131 additions and 37 deletions

View File

@ -0,0 +1,75 @@
%YAML:1.0
---
SGBM:
# must define for opencv check
name: StereoMatcher.SGBM
# Margin in percentage by which the best (minimum) computed cost function value should "win" the second best value to consider the found match correct.
# Normally, a value within the 5-15 range is good enough.
uniquenessRatio: 10
# Maximum size of smooth disparity regions to consider their noise speckles and invalidate.
# Set it to 0 to disable speckle filtering.
# Otherwise, set it somewhere in the 50-200 range.
speckleWindowSize: 100
# Maximum disparity variation within each connected component.
# If you do speckle filtering, set the parameter to a positive value, it will be implicitly multiplied by 16.
# Normally, 1 or 2 is good enough.
speckleRange: 32
# Minimum possible disparity value.
# Normally, it is zero but sometimes rectification algorithms
# can shift images, so this parameter needs to be adjusted accordingly.
minDisparity: 0
# Maximum allowed difference (in integer pixel units) in the left-right disparity check.
# Set it to a non-positive value to disable the check.
disp12MaxDiff: 1
# Truncation value for the prefiltered image pixels.
# The algorithm first computes x-derivative at each pixel and clips its value by [-preFilterCap, preFilterCap] interval.
# The result values are passed to the Birchfield-Tomasi pixel cost function.
preFilterCap: 63
# Maximum disparity minus minimum disparity.
# The value is always greater than zero.
# In the current implementation, this parameter must be divisible by 16.
numDisparities: 64
# Matched block size. It must be an odd number >=1 .
# Normally, it should be somewhere in the 3..11 range.
blockSize: 3
# The first parameter controlling the disparity smoothness. See below.
P1: 72
# The second parameter controlling the disparity smoothness.
# The larger the values are, the smoother the disparity is.
# P1 is the penalty on the disparity change by plus or minus 1 between neighbor pixels.
# P2 is the penalty on the disparity change by more than 1 between neighbor pixels.
# The algorithm requires P2 > P1 .
P2: 188
BM:
# must define for opencv check
name: StereoMatcher.BM
uniquenessRatio: 60
speckleWindowSize: 100
speckleRange: 4
minDisparity: 0
disp12MaxDiff: 1
preFilterCap: 31
# the disparity search range.
# For each pixel algorithm will find the best disparity from 0 (default minimum disparity) to numDisparities.
# The search range can then be shifted by changing the minimum disparity.
numDisparities: 64
# the linear size of the blocks compared by the algorithm.
# The size should be odd (as the block is centered at the current pixel).
# Larger block size implies smoother, though less accurate disparity map.
# Smaller block size gives more detailed disparity map,
# but there is higher chance for algorithm to find a wrong correspondence.
blockSize: 15
preFilterSize: 9
textureThreshold: 10

View File

@ -204,15 +204,6 @@ class MYNTEYE_API API {
* Get the intrinsics base of stream. * Get the intrinsics base of stream.
*/ */
std::shared_ptr<IntrinsicsBase> GetIntrinsicsBase(const Stream &stream) const; std::shared_ptr<IntrinsicsBase> GetIntrinsicsBase(const Stream &stream) const;
/**
* Get the intrinsics of stream.
*/
template <typename T>
T GetDisparityParams() const;
/**
* Get the intrinsics base of stream.
*/
std::shared_ptr<DisparityParamsBase> GetDisparityParamsBase() const;
/** /**
* Get the extrinsics from one stream to another. * Get the extrinsics from one stream to another.
*/ */
@ -368,6 +359,11 @@ class MYNTEYE_API API {
*/ */
std::shared_ptr<struct CameraROSMsgInfoPair> GetCameraROSMsgInfoPair(); std::shared_ptr<struct CameraROSMsgInfoPair> GetCameraROSMsgInfoPair();
/**
* Load disparity config from file.
*/
bool ConfigDisparityFromFile(const std::string& config_file);
private: private:
std::shared_ptr<Device> device_; std::shared_ptr<Device> device_;

View File

@ -644,33 +644,6 @@ enum class DisparityComputingMethod : std::uint8_t {
UNKNOW UNKNOW
}; };
struct MYNTEYE_API DisparityParamsBase {
DisparityParamsBase() {
disparity_model_ = DisparityComputingMethod::UNKNOW;
}
virtual ~DisparityParamsBase() {}
virtual void ResizeIntrinsics() {}
/** The calibration model */
DisparityComputingMethod disparity_model() const {
return disparity_model_;
}
protected:
DisparityComputingMethod disparity_model_;
};
struct MYNTEYE_API DisparityParamsSGBM : public DisparityParamsBase {
DisparityParamsSGBM() {
disparity_model_ = DisparityComputingMethod::SGBM;
}
};
struct MYNTEYE_API DisparityParamsBM : public DisparityParamsBase {
DisparityParamsBM() {
disparity_model_ = DisparityComputingMethod::BM;
}
};
/** /**
* @defgroup datatypes Datatypes * @defgroup datatypes Datatypes
* @brief Public data types. * @brief Public data types.

View File

@ -14,6 +14,7 @@
#include <opencv2/highgui/highgui.hpp> #include <opencv2/highgui/highgui.hpp>
#include "mynteye/api/api.h" #include "mynteye/api/api.h"
#include "mynteye/logger.h"
MYNTEYE_USE_NAMESPACE MYNTEYE_USE_NAMESPACE
@ -29,6 +30,21 @@ int main(int argc, char *argv[]) {
// api->EnableStreamData(Stream::DISPARITY); // api->EnableStreamData(Stream::DISPARITY);
api->EnableStreamData(Stream::DISPARITY_NORMALIZED); api->EnableStreamData(Stream::DISPARITY_NORMALIZED);
if (argc == 2) {
std::string config_path(argv[1]);
if (api->ConfigDisparityFromFile(config_path)) {
LOG(INFO) << "load disparity file: "
<< config_path
<< " success."
<< std::endl;
} else {
LOG(INFO) << "load disparity file: "
<< config_path
<< " failed."
<< std::endl;
}
}
api->SetDisparityComputingMethodType(DisparityComputingMethod::BM); api->SetDisparityComputingMethodType(DisparityComputingMethod::BM);
api->Start(Source::VIDEO_STREAMING); api->Start(Source::VIDEO_STREAMING);

View File

@ -604,4 +604,8 @@ std::shared_ptr<struct CameraROSMsgInfoPair> API::GetCameraROSMsgInfoPair() {
return synthetic_->GetCameraROSMsgInfoPair(); return synthetic_->GetCameraROSMsgInfoPair();
} }
bool API::ConfigDisparityFromFile(const std::string& config_file) {
return synthetic_->ConfigDisparityFromFile(config_file);
}
MYNTEYE_END_NAMESPACE MYNTEYE_END_NAMESPACE

View File

@ -17,6 +17,7 @@
#include <opencv2/calib3d/calib3d.hpp> #include <opencv2/calib3d/calib3d.hpp>
#include <opencv2/imgproc/imgproc.hpp> #include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/core/persistence.hpp>
#include "mynteye/logger.h" #include "mynteye/logger.h"
@ -103,6 +104,24 @@ void DisparityProcessor::SetDisparityComputingMethodType(
NotifyComputingTypeChanged(MethodType); NotifyComputingTypeChanged(MethodType);
} }
bool DisparityProcessor::ConfigFromFile(const std::string& config_file) {
cv::FileStorage fsSettings(config_file, cv::FileStorage::READ);
if (!fsSettings.isOpened()) {
std::cerr << "ERROR: Wrong path to settings" << std::endl;
return false;
}
cv::FileNode node_sgbm = fsSettings["SGBM"];
if (node_sgbm.type() == cv::FileNode::MAP) {
sgbm_matcher->read(node_sgbm);
}
cv::FileNode node_bm = fsSettings["BM"];
if (node_bm.type() == cv::FileNode::MAP) {
bm_matcher->read(node_bm);
}
return true;
}
std::string DisparityProcessor::Name() { std::string DisparityProcessor::Name() {
return NAME; return NAME;
} }

View File

@ -39,6 +39,7 @@ class DisparityProcessor : public Processor {
void SetDisparityComputingMethodType( void SetDisparityComputingMethodType(
const DisparityComputingMethod &MethodType); const DisparityComputingMethod &MethodType);
void NotifyComputingTypeChanged(const DisparityComputingMethod &MethodType); void NotifyComputingTypeChanged(const DisparityComputingMethod &MethodType);
bool ConfigFromFile(const std::string& config);
protected: protected:
// inline Processor::process_type ProcessOutputConnection() override { // inline Processor::process_type ProcessOutputConnection() override {

View File

@ -119,6 +119,12 @@ void Synthetic::NotifyImageParamsChanged() {
} }
} }
bool Synthetic::ConfigDisparityFromFile(const std::string& config_file) {
auto processor = getProcessorWithStream(Stream::DISPARITY);
auto proc = static_cast<DisparityProcessor*>(&(*processor));
return proc->ConfigFromFile(config_file);
}
const struct Synthetic::stream_control_t Synthetic::getControlDateWithStream( const struct Synthetic::stream_control_t Synthetic::getControlDateWithStream(
const Stream& stream) const { const Stream& stream) const {
for (auto &&it : processors_) { for (auto &&it : processors_) {

View File

@ -94,6 +94,7 @@ class Synthetic {
void SetDisparityComputingMethodType( void SetDisparityComputingMethodType(
const DisparityComputingMethod &MethoType); const DisparityComputingMethod &MethoType);
std::shared_ptr<struct CameraROSMsgInfoPair> GetCameraROSMsgInfoPair(); std::shared_ptr<struct CameraROSMsgInfoPair> GetCameraROSMsgInfoPair();
bool ConfigDisparityFromFile(const std::string& config_file);
private: private:
void InitCalibInfo(); void InitCalibInfo();

View File

@ -17,3 +17,6 @@
# index_s2_6: "6" # index_s2_6: "6"
standard2/request_index: 1 standard2/request_index: 1
# standard/frame_rate range: {10,15,20,25,30,35,40,45,50,55,60}
standard/frame_rate: 20