Public Attributes | List of all members
gtsam::SfmTrack Struct Reference

#include <SfmTrack.h>

Inheritance diagram for gtsam::SfmTrack:
Inheritance graph
[legend]

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 Point3point3 () 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 SfmMeasurementmeasurement (size_t idx) const
 Get the measurement (camera index, Point2) at pose index idx More...
 
const SiftIndexsiftIndex (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< SfmMeasurementmeasurements
 The 2D image projections (id,(u,v)) More...
 
std::vector< SiftIndexsiftIndices
 The feature descriptors (optional) More...
 

Detailed Description

Definition at line 125 of file SfmTrack.h.

Constructor & Destructor Documentation

◆ SfmTrack() [1/2]

gtsam::SfmTrack::SfmTrack ( float  r = 0,
float  g = 0,
float  b = 0 
)
inlineexplicit

Definition at line 132 of file SfmTrack.h.

◆ SfmTrack() [2/2]

gtsam::SfmTrack::SfmTrack ( const gtsam::Point3 pt,
float  r = 0,
float  g = 0,
float  b = 0 
)
inlineexplicit

Definition at line 135 of file SfmTrack.h.

Member Function Documentation

◆ equals()

bool gtsam::SfmTrack::equals ( const SfmTrack sfmTrack,
double  tol = 1e-9 
) const

assert equality up to a tolerance

Definition at line 30 of file SfmTrack.cpp.

◆ point3()

const Point3& gtsam::SfmTrack::point3 ( ) const
inline

Get 3D point.

Definition at line 144 of file SfmTrack.h.

◆ print()

void gtsam::SfmTrack::print ( const std::string &  s = "") const

print

Definition at line 25 of file SfmTrack.cpp.

◆ rgb()

Point3 gtsam::SfmTrack::rgb ( ) const
inline

Get RGB values describing 3d point.

Definition at line 147 of file SfmTrack.h.

Member Data Documentation

◆ b

float gtsam::SfmTrack::b

RGB color of the 3D point.

Definition at line 127 of file SfmTrack.h.

◆ g

float gtsam::SfmTrack::g

Definition at line 127 of file SfmTrack.h.

◆ p

Point3 gtsam::SfmTrack::p

3D position of the point

Definition at line 126 of file SfmTrack.h.

◆ r

float gtsam::SfmTrack::r

Definition at line 127 of file SfmTrack.h.


The documentation for this struct was generated from the following files:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:08