#include <SfmTrack.h>
Public Member Functions | |
Constructors | |
SfmTrack (float r=0, float g=0, float b=0) | |
SfmTrack (const gtsam::Point3 &pt, float r=0, float g=0, float b=0) | |
Standard Interface | |
const Point3 & | point3 () const |
Get 3D point. More... | |
Point3 | rgb () const |
Get RGB values describing 3d point. More... | |
Testable | |
void | print (const std::string &s="") const |
print More... | |
bool | equals (const SfmTrack &sfmTrack, double tol=1e-9) const |
assert equality up to a tolerance More... | |
Public Member Functions inherited from gtsam::SfmTrack2d | |
SfmTrack2d ()=default | |
SfmTrack2d (const std::vector< SfmMeasurement > &measurements) | |
void | addMeasurement (size_t idx, const gtsam::Point2 &m) |
Add measurement (camera_idx, Point2) to track. More... | |
size_t | numberMeasurements () const |
Total number of measurements in this track. More... | |
const SfmMeasurement & | measurement (size_t idx) const |
Get the measurement (camera index, Point2) at pose index idx More... | |
const SiftIndex & | siftIndex (size_t idx) const |
Get the SIFT feature index corresponding to the measurement at idx More... | |
bool | hasUniqueCameras () const |
Check that no two measurements are from the same camera. More... | |
Eigen::MatrixX2d | measurementMatrix () const |
Return the measurements as a 2D matrix. More... | |
Eigen::VectorXi | indexVector () const |
Return the camera indices of the measurements. More... | |
Public Attributes | |
float | b |
RGB color of the 3D point. More... | |
float | g |
Point3 | p |
3D position of the point More... | |
float | r |
Public Attributes inherited from gtsam::SfmTrack2d | |
std::vector< SfmMeasurement > | measurements |
The 2D image projections (id,(u,v)) More... | |
std::vector< SiftIndex > | siftIndices |
The feature descriptors (optional) More... | |
Definition at line 125 of file SfmTrack.h.
|
inlineexplicit |
Definition at line 132 of file SfmTrack.h.
|
inlineexplicit |
Definition at line 135 of file SfmTrack.h.
assert equality up to a tolerance
Definition at line 30 of file SfmTrack.cpp.
|
inline |
Get 3D point.
Definition at line 144 of file SfmTrack.h.
void gtsam::SfmTrack::print | ( | const std::string & | s = "" | ) | const |
Definition at line 25 of file SfmTrack.cpp.
|
inline |
Get RGB values describing 3d point.
Definition at line 147 of file SfmTrack.h.
float gtsam::SfmTrack::b |
RGB color of the 3D point.
Definition at line 127 of file SfmTrack.h.
float gtsam::SfmTrack::g |
Definition at line 127 of file SfmTrack.h.
Point3 gtsam::SfmTrack::p |
3D position of the point
Definition at line 126 of file SfmTrack.h.
float gtsam::SfmTrack::r |
Definition at line 127 of file SfmTrack.h.