Skip to content

Commit

Permalink
add stereo constraints
Browse files Browse the repository at this point in the history
  • Loading branch information
raphaelchang committed Sep 19, 2019
1 parent de601d9 commit 6ee9c3b
Show file tree
Hide file tree
Showing 2 changed files with 43 additions and 4 deletions.
21 changes: 18 additions & 3 deletions src/optimization/bundle_adjuster.cc
Original file line number Diff line number Diff line change
Expand Up @@ -110,13 +110,28 @@ bool BundleAdjuster::Optimize(std::vector<data::Landmark> &landmarks)
continue;
}
ceres::CostFunction *cost_function = nullptr;
const data::Feature *stereoFeat = feature.GetFrame().HasStereoImage() ? landmark.GetStereoObservationByFrameID(feature.GetFrame().GetID()) : nullptr;
if (feature.GetFrame().GetCameraModel().GetType() == camera::CameraModel<>::kPerspective)
{
cost_function = ReprojectionError<camera::Perspective>::Create(feature);
if (stereoFeat != nullptr)
{
cost_function = ReprojectionError<camera::Perspective>::Create(feature, *stereoFeat);
}
else
{
cost_function = ReprojectionError<camera::Perspective>::Create(feature);
}
}
else if (feature.GetFrame().GetCameraModel().GetType() == camera::CameraModel<>::kDoubleSphere)
{
cost_function = ReprojectionError<camera::DoubleSphere>::Create(feature);
if (stereoFeat != nullptr)
{
cost_function = ReprojectionError<camera::DoubleSphere>::Create(feature, *stereoFeat);
}
else
{
cost_function = ReprojectionError<camera::DoubleSphere>::Create(feature);
}
}
if (cost_function != nullptr)
{
Expand All @@ -142,7 +157,7 @@ bool BundleAdjuster::Optimize(std::vector<data::Landmark> &landmarks)
bool hasEstCameraPoses = false;
for (const data::Feature &feature : landmark.GetObservations())
{
if (feature.GetFrame().HasEstimatedPose())
if (feature.GetFrame().HasEstimatedPose() && feature.GetFrame().IsEstimatedByLandmark(landmark.GetID()))
{
hasEstCameraPoses = true;
}
Expand Down
26 changes: 25 additions & 1 deletion src/optimization/reprojection_error.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,16 @@ class ReprojectionError
{
public:
ReprojectionError(const data::Feature &feature)
: feature_(feature)
: feature_(feature),
stereoFeature_(feature),
hasStereo_(false)
{
}

ReprojectionError(const data::Feature &feature, const data::Feature &stereo_feature)
: feature_(feature),
stereoFeature_(stereo_feature),
hasStereo_(true)
{
}

Expand All @@ -32,6 +41,14 @@ class ReprojectionError
camera.ProjectToImage(camPt, reprojPoint);
reproj_error[0] = reprojPoint(0) - T(feature_.GetKeypoint().pt.x);
reproj_error[1] = reprojPoint(1) - T(feature_.GetKeypoint().pt.y);
if (hasStereo_ && stereoFeature_.GetFrame().HasStereoImage())
{
Matrix<T, 2, 1> reprojPoint2;
Matrix<T, 3, 4> stereoPose = stereoFeature_.GetFrame().GetStereoPose().cast<T>();
camera.ProjectToImage(util::TFUtil::TransformPoint(stereoPose, camPt), reprojPoint2);
reproj_error[0] += reprojPoint(0) - T(stereoFeature_.GetKeypoint().pt.x);
reproj_error[1] += reprojPoint(1) - T(stereoFeature_.GetKeypoint().pt.y);
}
return true;
}

Expand All @@ -40,8 +57,15 @@ class ReprojectionError
return new ceres::AutoDiffCostFunction<ReprojectionError, 2, 4, 3, 3>(new ReprojectionError<C>(feature));
}

static ceres::CostFunction* Create(const data::Feature &feature, const data::Feature &stereo_feature)
{
return new ceres::AutoDiffCostFunction<ReprojectionError, 2, 4, 3, 3>(new ReprojectionError<C>(feature, stereo_feature));
}

private:
const data::Feature feature_;
const data::Feature stereoFeature_;
bool hasStereo_;
};

}
Expand Down

0 comments on commit 6ee9c3b

Please sign in to comment.