Consistent interface for pixel center (#579)
* defined u0 and v0 in all camera models for consistent interface * deprecate u0/v0 and use px/py everywhere * Use deprecation macro * fix various issuesrelease/4.3a0
parent
aab11ea155
commit
6c6cb965d8
|
|
@ -98,6 +98,17 @@ public:
|
||||||
return k2_;
|
return k2_;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/// image center in x
|
||||||
|
inline double px() const {
|
||||||
|
return u0_;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// image center in y
|
||||||
|
inline double py() const {
|
||||||
|
return v0_;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
|
||||||
/// get parameter u0
|
/// get parameter u0
|
||||||
inline double u0() const {
|
inline double u0() const {
|
||||||
return u0_;
|
return u0_;
|
||||||
|
|
@ -107,6 +118,7 @@ public:
|
||||||
inline double v0() const {
|
inline double v0() const {
|
||||||
return v0_;
|
return v0_;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
||||||
|
|
@ -597,6 +597,7 @@ class Rot3 {
|
||||||
Rot3(double R11, double R12, double R13,
|
Rot3(double R11, double R12, double R13,
|
||||||
double R21, double R22, double R23,
|
double R21, double R22, double R23,
|
||||||
double R31, double R32, double R33);
|
double R31, double R32, double R33);
|
||||||
|
Rot3(double w, double x, double y, double z);
|
||||||
|
|
||||||
static gtsam::Rot3 Rx(double t);
|
static gtsam::Rot3 Rx(double t);
|
||||||
static gtsam::Rot3 Ry(double t);
|
static gtsam::Rot3 Ry(double t);
|
||||||
|
|
@ -980,8 +981,8 @@ class Cal3Bundler {
|
||||||
double fy() const;
|
double fy() const;
|
||||||
double k1() const;
|
double k1() const;
|
||||||
double k2() const;
|
double k2() const;
|
||||||
double u0() const;
|
double px() const;
|
||||||
double v0() const;
|
double py() const;
|
||||||
Vector vector() const;
|
Vector vector() const;
|
||||||
Vector k() const;
|
Vector k() const;
|
||||||
Matrix K() const;
|
Matrix K() const;
|
||||||
|
|
@ -2761,7 +2762,16 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor {
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/slam/dataset.h>
|
#include <gtsam/slam/dataset.h>
|
||||||
|
|
||||||
class SfmTrack {
|
class SfmTrack {
|
||||||
|
SfmTrack();
|
||||||
|
|
||||||
|
double r;
|
||||||
|
double g;
|
||||||
|
double b;
|
||||||
|
// TODO Need to close wrap#10 to allow this to work.
|
||||||
|
// std::vector<pair<size_t, gtsam::Point2>> measurements;
|
||||||
|
|
||||||
Point3 point3() const;
|
Point3 point3() const;
|
||||||
size_t number_measurements() const;
|
size_t number_measurements() const;
|
||||||
pair<size_t, gtsam::Point2> measurement(size_t idx) const;
|
pair<size_t, gtsam::Point2> measurement(size_t idx) const;
|
||||||
|
|
|
||||||
|
|
@ -41,7 +41,7 @@ struct Cal3Bundler0 : public Cal3Bundler {
|
||||||
double v0 = 0)
|
double v0 = 0)
|
||||||
: Cal3Bundler(f, k1, k2, u0, v0) {}
|
: Cal3Bundler(f, k1, k2, u0, v0) {}
|
||||||
Cal3Bundler0 retract(const Vector& d) const {
|
Cal3Bundler0 retract(const Vector& d) const {
|
||||||
return Cal3Bundler0(fx() + d(0), k1() + d(1), k2() + d(2), u0(), v0());
|
return Cal3Bundler0(fx() + d(0), k1() + d(1), k2() + d(2), px(), py());
|
||||||
}
|
}
|
||||||
Vector3 localCoordinates(const Cal3Bundler0& T2) const {
|
Vector3 localCoordinates(const Cal3Bundler0& T2) const {
|
||||||
return T2.vector() - vector();
|
return T2.vector() - vector();
|
||||||
|
|
|
||||||
|
|
@ -1164,8 +1164,8 @@ bool writeBAL(const string &filename, SfmData &data) {
|
||||||
for (size_t k = 0; k < track.number_measurements();
|
for (size_t k = 0; k < track.number_measurements();
|
||||||
k++) { // for each observation of the 3D point j
|
k++) { // for each observation of the 3D point j
|
||||||
size_t i = track.measurements[k].first; // camera id
|
size_t i = track.measurements[k].first; // camera id
|
||||||
double u0 = data.cameras[i].calibration().u0();
|
double u0 = data.cameras[i].calibration().px();
|
||||||
double v0 = data.cameras[i].calibration().v0();
|
double v0 = data.cameras[i].calibration().py();
|
||||||
|
|
||||||
if (u0 != 0 || v0 != 0) {
|
if (u0 != 0 || v0 != 0) {
|
||||||
cout << "writeBAL has not been tested for calibration with nonzero "
|
cout << "writeBAL has not been tested for calibration with nonzero "
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue