34 #include <opencv2/imgproc/types_c.h> 37 #include <libfovis/fovis.hpp> 55 if(parameters.find(Parameters::kOdomVisKeyFrameThr()) != parameters.end())
57 fovisParameters_.insert(*parameters.find(Parameters::kOdomVisKeyFrameThr()));
122 UERROR(
"Not supported input!");
132 UERROR(
"Invalid camera model! Mono cameras=%d (reproj=%d), Stereo camera=%d (reproj=%d|%d)",
142 if(data.
imageRaw().type() == CV_8UC3)
144 cv::cvtColor(data.
imageRaw(), gray, CV_BGR2GRAY);
146 else if(data.
imageRaw().type() == CV_8UC1)
152 UFATAL(
"Not supported color type!");
155 fovis::VisualOdometryOptions options;
156 if(fovis_ == 0 || (data.
cameraModels().size() != 1 && stereoDepth_ == 0))
158 options = fovis::VisualOdometry::getDefaultOptions();
161 options[
"feature-window-size"] =
uValue(
fovisParameters_, Parameters::kOdomFovisFeatureWindowSize(), defaults.at(Parameters::kOdomFovisFeatureWindowSize()));
162 options[
"max-pyramid-level"] =
uValue(
fovisParameters_, Parameters::kOdomFovisMaxPyramidLevel(), defaults.at(Parameters::kOdomFovisMaxPyramidLevel()));
163 options[
"min-pyramid-level"] =
uValue(
fovisParameters_, Parameters::kOdomFovisMinPyramidLevel(), defaults.at(Parameters::kOdomFovisMinPyramidLevel()));
164 options[
"target-pixels-per-feature"] =
uValue(
fovisParameters_, Parameters::kOdomFovisTargetPixelsPerFeature(), defaults.at(Parameters::kOdomFovisTargetPixelsPerFeature()));
165 options[
"fast-threshold"] =
uValue(
fovisParameters_, Parameters::kOdomFovisFastThreshold(), defaults.at(Parameters::kOdomFovisFastThreshold()));
166 options[
"use-adaptive-threshold"] =
uValue(
fovisParameters_, Parameters::kOdomFovisUseAdaptiveThreshold(), defaults.at(Parameters::kOdomFovisUseAdaptiveThreshold()));
167 options[
"fast-threshold-adaptive-gain"] =
uValue(
fovisParameters_, Parameters::kOdomFovisFastThresholdAdaptiveGain(), defaults.at(Parameters::kOdomFovisFastThresholdAdaptiveGain()));
168 options[
"use-homography-initialization"] =
uValue(
fovisParameters_, Parameters::kOdomFovisUseHomographyInitialization(), defaults.at(Parameters::kOdomFovisUseHomographyInitialization()));
172 options[
"use-bucketing"] =
uValue(
fovisParameters_, Parameters::kOdomFovisUseBucketing(), defaults.at(Parameters::kOdomFovisUseBucketing()));
173 options[
"bucket-width"] =
uValue(
fovisParameters_, Parameters::kOdomFovisBucketWidth(), defaults.at(Parameters::kOdomFovisBucketWidth()));
174 options[
"bucket-height"] =
uValue(
fovisParameters_, Parameters::kOdomFovisBucketHeight(), defaults.at(Parameters::kOdomFovisBucketHeight()));
175 options[
"max-keypoints-per-bucket"] =
uValue(
fovisParameters_, Parameters::kOdomFovisMaxKeypointsPerBucket(), defaults.at(Parameters::kOdomFovisMaxKeypointsPerBucket()));
176 options[
"use-image-normalization"] =
uValue(
fovisParameters_, Parameters::kOdomFovisUseImageNormalization(), defaults.at(Parameters::kOdomFovisUseImageNormalization()));
179 options[
"inlier-max-reprojection-error"] =
uValue(
fovisParameters_, Parameters::kOdomFovisInlierMaxReprojectionError(), defaults.at(Parameters::kOdomFovisInlierMaxReprojectionError()));
180 options[
"clique-inlier-threshold"] =
uValue(
fovisParameters_, Parameters::kOdomFovisCliqueInlierThreshold(), defaults.at(Parameters::kOdomFovisCliqueInlierThreshold()));
181 options[
"min-features-for-estimate"] =
uValue(
fovisParameters_, Parameters::kOdomFovisMinFeaturesForEstimate(), defaults.at(Parameters::kOdomFovisMinFeaturesForEstimate()));
182 options[
"max-mean-reprojection-error"] =
uValue(
fovisParameters_, Parameters::kOdomFovisMaxMeanReprojectionError(), defaults.at(Parameters::kOdomFovisMaxMeanReprojectionError()));
183 options[
"use-subpixel-refinement"] =
uValue(
fovisParameters_, Parameters::kOdomFovisUseSubpixelRefinement(), defaults.at(Parameters::kOdomFovisUseSubpixelRefinement()));
184 options[
"feature-search-window"] =
uValue(
fovisParameters_, Parameters::kOdomFovisFeatureSearchWindow(), defaults.at(Parameters::kOdomFovisFeatureSearchWindow()));
185 options[
"update-target-features-with-refined"] =
uValue(
fovisParameters_, Parameters::kOdomFovisUpdateTargetFeaturesWithRefined(), defaults.at(Parameters::kOdomFovisUpdateTargetFeaturesWithRefined()));
188 options[
"stereo-require-mutual-match"] =
uValue(
fovisParameters_, Parameters::kOdomFovisStereoRequireMutualMatch(), defaults.at(Parameters::kOdomFovisStereoRequireMutualMatch()));
189 options[
"stereo-max-dist-epipolar-line"] =
uValue(
fovisParameters_, Parameters::kOdomFovisStereoMaxDistEpipolarLine(), defaults.at(Parameters::kOdomFovisStereoMaxDistEpipolarLine()));
190 options[
"stereo-max-refinement-displacement"] =
uValue(
fovisParameters_, Parameters::kOdomFovisStereoMaxRefinementDisplacement(), defaults.at(Parameters::kOdomFovisStereoMaxRefinementDisplacement()));
191 options[
"stereo-max-disparity"] =
uValue(
fovisParameters_, Parameters::kOdomFovisStereoMaxDisparity(), defaults.at(Parameters::kOdomFovisStereoMaxDisparity()));
194 fovis::DepthSource * depthSource = 0;
201 fovis::CameraIntrinsicsParameters rgb_params;
202 memset(&rgb_params, 0,
sizeof(fovis::CameraIntrinsicsParameters));
204 rgb_params.height = data.
cameraModels()[0].imageHeight();
210 localTransform = data.
cameraModels()[0].localTransform();
214 UINFO(
"Init rgbd fovis: %dx%d fx=%f fy=%f cx=%f cy=%f", rgb_params.width, rgb_params.height, rgb_params.fx, rgb_params.fy, rgb_params.cx, rgb_params.cy);
215 rect_ =
new fovis::Rectification(rgb_params);
220 depthImage_ =
new fovis::DepthImage(rgb_params, rgb_params.width, rgb_params.height);
223 if(data.
depthRaw().type() == CV_32FC1)
226 for(
int i=0; i<depth.rows; ++i)
228 for(
int j=0; j<depth.cols; ++j)
230 float &
d = depth.at<
float>(i,j);
238 else if(data.
depthRaw().type() == CV_16UC1)
240 depth = cv::Mat(data.
depthRaw().size(), CV_32FC1);
241 for(
int i=0; i<data.
depthRaw().rows; ++i)
243 for(
int j=0; j<data.
depthRaw().cols; ++j)
245 float d = float(data.
depthRaw().at<
unsigned short>(i,j))/1000.0f;
246 depth.at<
float>(i, j) = d==0.0
f?NAN:d;
252 UFATAL(
"Unknown depth format!");
254 depthImage_->setDepthImage((
float*)depth.data);
255 depthSource = depthImage_;
261 fovis::CameraIntrinsicsParameters left_parameters;
272 UINFO(
"Init stereo fovis: %dx%d fx=%f fy=%f cx=%f cy=%f", left_parameters.width, left_parameters.height, left_parameters.fx, left_parameters.fy, left_parameters.cx, left_parameters.cy);
273 rect_ =
new fovis::Rectification(left_parameters);
276 if(stereoCalib_ == 0)
279 fovis::CameraIntrinsicsParameters right_parameters;
289 fovis::StereoCalibrationParameters stereo_parameters;
290 stereo_parameters.left_parameters = left_parameters;
291 stereo_parameters.right_parameters = right_parameters;
292 stereo_parameters.right_to_left_rotation[0] = 1.0;
293 stereo_parameters.right_to_left_rotation[1] = 0.0;
294 stereo_parameters.right_to_left_rotation[2] = 0.0;
295 stereo_parameters.right_to_left_rotation[3] = 0.0;
297 stereo_parameters.right_to_left_translation[1] = 0.0;
298 stereo_parameters.right_to_left_translation[2] = 0.0;
300 stereoCalib_ =
new fovis::StereoCalibration(stereo_parameters);
303 if(stereoDepth_ == 0)
305 stereoDepth_ =
new fovis::StereoDepth(stereoCalib_, options);
307 if(data.
rightRaw().type() == CV_8UC3)
309 cv::cvtColor(data.
rightRaw(), right, CV_BGR2GRAY);
311 else if(data.
rightRaw().type() == CV_8UC1)
317 UFATAL(
"Not supported color type!");
319 stereoDepth_->setRightImage(right.data);
320 depthSource = stereoDepth_;
325 fovis_ =
new fovis::VisualOdometry(rect_, options);
329 fovis_->processFrame(gray.data, depthSource);
335 fovis::MotionEstimateStatusCode statusCode = fovis_->getMotionEstimator()->getMotionEstimateStatus();
336 if(statusCode > fovis::SUCCESS)
338 UWARN(
"Fovis error status: %s", fovis::MotionEstimateStatusCodeStrings[statusCode]);
341 covariance = cv::Mat::eye(6,6, CV_64FC1)*9999.0;
348 covariance = cv::Mat::eye(6,6, CV_64FC1)*9999.0;
353 const Eigen::MatrixXd& cov = fovis_->getMotionEstimator()->getMotionEstimateCov();
354 if(cov.cols() == 6 && cov.rows() == 6 && cov(0,0) > 0.0)
356 covariance = cv::Mat::eye(6,6, CV_64FC1);
357 memcpy(covariance.data, cov.data(), 36*
sizeof(double));
371 t = localTransform * t * localTransform.
inverse();
380 info->
features = fovis_->getTargetFrame()->getNumDetectedKeypoints();
381 info->
reg.
matches = fovis_->getMotionEstimator()->getNumMatches();
382 info->
reg.
inliers = fovis_->getMotionEstimator()->getNumInliers();
387 const fovis::FeatureMatch * matches = fovis_->getMotionEstimator()->getMatches();
388 int numMatches = fovis_->getMotionEstimator()->getNumMatches();
389 if(matches && numMatches>0)
395 for (
int i = 0; i < numMatches; ++i)
397 info->
refCorners[i].x = matches[i].ref_keypoint->base_uv[0];
398 info->
refCorners[i].y = matches[i].ref_keypoint->base_uv[1];
399 info->
newCorners[i].x = matches[i].target_keypoint->base_uv[0];
400 info->
newCorners[i].y = matches[i].target_keypoint->base_uv[1];
408 UINFO(
"Odom update time = %fs status=%s", timer.
elapsed(), fovis::MotionEstimateStatusCodeStrings[statusCode]);
411 UERROR(
"RTAB-Map is not built with FOVIS support! Select another visual odometry approach.");
static ParametersMap filterParameters(const ParametersMap ¶meters, const std::string &group)
std::vector< cv::Point2f > refCorners
bool isInfoDataFilled() const
virtual void reset(const Transform &initialPose=Transform::getIdentity())
OdometryFovis(const rtabmap::ParametersMap ¶meters=rtabmap::ParametersMap())
std::map< std::string, std::string > ParametersMap
const cv::Mat & imageRaw() const
Wrappers of STL for convenient functions.
bool isValidForProjection() const
const CameraModel & left() const
std::vector< int > cornerInliers
ParametersMap fovisParameters_
const cv::Mat & depthOrRightRaw() const
bool isValidForReprojection() const
static const ParametersMap & getDefaultParameters()
const std::vector< CameraModel > & cameraModels() const
const CameraModel & right() const
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
std::vector< cv::Point2f > newCorners
Transform previousLocalTransform_
virtual void reset(const Transform &initialPose=Transform::getIdentity())
const Transform & localTransform() const
std::string UTILITE_EXP uNumber2Str(unsigned int number)
virtual Transform computeTransform(SensorData &image, const Transform &guess=Transform(), OdometryInfo *info=0)
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())