36 #include <viso_stereo.h> 38 double computeFeatureFlow(
const std::vector<Matcher::p_match>& matches)
40 double total_flow = 0.0;
41 for (
size_t i = 0; i < matches.size(); ++i)
43 double x_diff = matches[i].u1c - matches[i].u1p;
44 double y_diff = matches[i].v1c - matches[i].v1p;
45 total_flow +=
sqrt(x_diff * x_diff + y_diff * y_diff);
47 return total_flow / matches.size();
57 ref_frame_change_method_(0),
58 ref_frame_inlier_threshold_(
Parameters::defaultOdomVisKeyFrameThr()),
59 ref_frame_motion_threshold_(5.0),
61 keep_reference_frame_(
false),
63 reference_motion_(
Transform::getIdentity())
66 Parameters::parse(parameters, Parameters::kOdomVisKeyFrameThr(), ref_frame_inlier_threshold_);
107 UERROR(
"viso2 odometry doesn't support RGB-D data, only stereo. Aborting odometry update...");
115 UERROR(
"Not compatible left (%dx%d) or right (%dx%d) image.",
127 UERROR(
"Invalid stereo camera model!");
132 if(data.
imageRaw().type() == CV_8UC3)
134 cv::cvtColor(data.
imageRaw(), leftGray, CV_BGR2GRAY);
136 else if(data.
imageRaw().type() == CV_8UC1)
142 UFATAL(
"Not supported color type!");
145 if(data.
rightRaw().type() == CV_8UC3)
147 cv::cvtColor(data.
rightRaw(), rightGray, CV_BGR2GRAY);
149 else if(data.
rightRaw().type() == CV_8UC1)
155 UFATAL(
"Not supported color type!");
158 int32_t dims[] = {leftGray.cols, leftGray.rows, leftGray.cols};
162 VisualOdometryStereo::parameters params;
179 bool multistage = Parameters::defaultOdomViso2MatchMultiStage();
180 bool halfResolution = Parameters::defaultOdomViso2MatchHalfResolution();
183 params.match.multi_stage = multistage?1:0;
184 params.match.half_resolution = halfResolution?1:0;
191 viso2_ =
new VisualOdometryStereo(params);
193 viso2_->process(leftGray.data, rightGray.data, dims);
195 covariance = cv::Mat::eye(6,6, CV_64FC1)*9999.0;
199 bool success = viso2_->process(leftGray.data, rightGray.data, dims, lost_ || keep_reference_frame_);
202 Matrix motionViso = Matrix::inv(viso2_->getMotion());
203 Transform motion(motionViso.val[0][0], motionViso.val[0][1], motionViso.val[0][2],motionViso.val[0][3],
204 motionViso.val[1][0], motionViso.val[1][1], motionViso.val[1][2],motionViso.val[1][3],
205 motionViso.val[2][0], motionViso.val[2][1], motionViso.val[2][2], motionViso.val[2][3]);
208 if(lost_ || keep_reference_frame_)
214 camera_motion = motion;
221 covariance = cv::Mat::eye(6,6, CV_64FC1);
222 covariance.at<
double>(0,0) = 0.002;
223 covariance.at<
double>(1,1) = 0.002;
224 covariance.at<
double>(2,2) = 0.05;
225 covariance.at<
double>(3,3) = 0.09;
226 covariance.at<
double>(4,4) = 0.09;
227 covariance.at<
double>(5,5) = 0.09;
233 covariance = cv::Mat::eye(6,6, CV_64FC1)*9999.0;
240 if(ref_frame_change_method_==1)
243 double feature_flow = computeFeatureFlow(viso2_->getMatches());
244 keep_reference_frame_ = (feature_flow < ref_frame_motion_threshold_);
248 keep_reference_frame_ = ref_frame_inlier_threshold_==0 || viso2_->getNumberOfInliers() > ref_frame_inlier_threshold_;
253 keep_reference_frame_ =
false;
267 t = localTransform * t * localTransform.
inverse();
276 info->
reg.
matches = viso2_->getNumberOfMatches();
277 info->
reg.
inliers = viso2_->getNumberOfInliers();
278 if(covariance.cols == 6 && covariance.rows == 6 && covariance.type() == CV_64FC1)
285 std::vector<Matcher::p_match> matches = viso2_->getMatches();
289 for (
size_t i = 0; i < matches.size(); ++i)
300 UINFO(
"Odom update time = %fs lost=%s", timer.
elapsed(), lost_?
"true":
"false");
303 UERROR(
"RTAB-Map is not built with VISO2 support! Select another visual odometry approach.");
Transform previousLocalTransform_
static ParametersMap filterParameters(const ParametersMap ¶meters, const std::string &group)
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
std::vector< cv::Point2f > refCorners
bool isInfoDataFilled() const
virtual void reset(const Transform &initialPose=Transform::getIdentity())
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
std::map< std::string, std::string > ParametersMap
const cv::Mat & imageRaw() const
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Wrappers of STL for convenient functions.
bool isValidForProjection() const
const CameraModel & left() const
std::vector< int > cornerInliers
bool isValidForReprojection() const
const CameraModel & right() const
ParametersMap viso2Parameters_
OdometryViso2(const rtabmap::ParametersMap ¶meters=rtabmap::ParametersMap())
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
std::vector< cv::Point2f > newCorners
virtual Transform computeTransform(SensorData &image, const Transform &guess=Transform(), OdometryInfo *info=0)
const Transform & localTransform() const
Transform reference_motion_