rename get3dPoint() to point3()
parent
34f670e9d5
commit
e6057fc4fa
|
@ -2847,7 +2847,7 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor {
|
||||||
|
|
||||||
#include <gtsam/slam/dataset.h>
|
#include <gtsam/slam/dataset.h>
|
||||||
class SfmTrack {
|
class SfmTrack {
|
||||||
Point3 get3dPoint() 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;
|
||||||
pair<size_t, size_t> siftIndex(size_t idx) const;
|
pair<size_t, size_t> siftIndex(size_t idx) const;
|
||||||
|
|
|
@ -233,7 +233,7 @@ struct SfmTrack {
|
||||||
SiftIndex siftIndex(size_t idx) const {
|
SiftIndex siftIndex(size_t idx) const {
|
||||||
return siftIndices[idx];
|
return siftIndices[idx];
|
||||||
}
|
}
|
||||||
Point3 get3dPoint() const {
|
Point3 point3() const {
|
||||||
return p;
|
return p;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue