-
Notifications
You must be signed in to change notification settings - Fork 789
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
Changes from 1 commit
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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); | ||
|
||
static gtsam::Rot3 Rx(double t); | ||
static gtsam::Rot3 Ry(double t); | ||
|
@@ -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; | ||
|
@@ -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; | ||
|
@@ -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; | ||
}; | ||
|
@@ -2761,7 +2768,16 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor { | |
}; | ||
|
||
#include <gtsam/slam/dataset.h> | ||
|
||
class SfmTrack { | ||
SfmTrack(); | ||
|
||
double r; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. double r,g,b; There was a problem hiding this comment. Choose a reason for hiding this commentThe 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. | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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; | ||
|
There was a problem hiding this comment.
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?)
There was a problem hiding this comment.
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.