Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Consistent interface for pixel center #579

Merged
merged 4 commits into from
Nov 4, 2020
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions gtsam/geometry/Cal3DS2_Base.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,12 @@ class GTSAM_EXPORT Cal3DS2_Base {
/// image center in y
inline double py() const { return v0_;}

/// image center in x
inline double u0() const { return u0_; }

/// image center in y
inline double v0() const { return v0_; }

/// First distortion coefficient
inline double k1() const { return k1_;}

Expand Down
6 changes: 6 additions & 0 deletions gtsam/geometry/Cal3Fisheye.h
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,12 @@ class GTSAM_EXPORT Cal3Fisheye {
/// image center in y
inline double py() const { return v0_; }

/// image center in x
inline double u0() const { return u0_; }

/// image center in y
inline double v0() const { return v0_; }

/// First distortion coefficient
inline double k1() const { return k1_; }

Expand Down
6 changes: 6 additions & 0 deletions gtsam/geometry/Cal3_S2.h
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,12 @@ class GTSAM_EXPORT Cal3_S2 {
return v0_;
}

/// image center in x
inline double u0() const { return u0_; }

/// image center in y
inline double v0() const { return v0_; }

/// return the principal point
Point2 principalPoint() const {
return Point2(u0_, v0_);
Expand Down
6 changes: 6 additions & 0 deletions gtsam/geometry/Cal3_S2Stereo.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,12 @@ namespace gtsam {
/// image center in y
inline double py() const { return K_.py();}

/// image center in x
inline double u0() const { return K_.px(); }

/// image center in y
inline double v0() const { return K_.py(); }

/// return the principal point
Point2 principalPoint() const { return K_.principalPoint();}

Expand Down
16 changes: 16 additions & 0 deletions gtsam/gtsam.i
Original file line number Diff line number Diff line change
Expand Up @@ -597,6 +597,7 @@ class Rot3 {
Rot3(double R11, double R12, double R13,
double R21, double R22, double R23,
double R31, double R32, double R33);
Rot3(double w, double x, double y, double z);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this related to this PR? (I'm assuming it's a quaternion rot constructor?)

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It isn't, but it was minor and I didn't want to create a whole new PR for it.


static gtsam::Rot3 Rx(double t);
static gtsam::Rot3 Ry(double t);
Expand Down Expand Up @@ -848,6 +849,8 @@ class Cal3_S2 {
double skew() const;
double px() const;
double py() const;
double u0() const;
double v0() const;
gtsam::Point2 principalPoint() const;
Vector vector() const;
Matrix K() const;
Expand All @@ -872,6 +875,8 @@ virtual class Cal3DS2_Base {
double skew() const;
double px() const;
double py() const;
double u0() const;
double v0() const;
double k1() const;
double k2() const;
Matrix K() const;
Expand Down Expand Up @@ -950,6 +955,8 @@ class Cal3_S2Stereo {
double skew() const;
double px() const;
double py() const;
double u0() const;
double v0() const;
gtsam::Point2 principalPoint() const;
double baseline() const;
};
Expand Down Expand Up @@ -2761,7 +2768,16 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor {
};

#include <gtsam/slam/dataset.h>

class SfmTrack {
SfmTrack();

double r;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

double r,g,b;

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The wrap parser doesn't support this syntax. :(

double g;
double b;
//TODO Need to close wrap#10 to allow this to work.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please use Google-style linting, which should flag an issue here.

// std::vector<pair<size_t, gtsam::Point2>> measurements;

Point3 point3() const;
size_t number_measurements() const;
pair<size_t, gtsam::Point2> measurement(size_t idx) const;
Expand Down