Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
SDFTracker Class Reference

#include <sdf_tracker.h>

List of all members.

Public Member Functions

virtual Vector6d EstimatePoseFromDepth (void)
 Estimates the incremental pose change vector from the current pose, relative to the current depth map.
virtual Vector6d EstimatePoseFromPoints (void)
 Estimates the incremental pose change vector from the current pose, relative to the current point vector.
virtual void FuseDepth (void)
 Fuses the current depth map into the TSDF volume, the current depth map is set using UpdateDepth.
virtual void FuseDepth (const cv::Mat &depth)
 Estimates the pose, fuses the given depth map and renders a virtual depth map (all in one)
virtual void FusePoints (void)
 Fuses the current point vector into the TSDF volume, the current point vector is set using UpdatePoints.
Eigen::Matrix4d GetCurrentTransformation (void)
 gets the current transformation matrix
void GetDenoisedImage (cv::Mat &img)
 gets the denoised image produced by Render.
virtual void LoadSDF (const std::string &filename)
 Loads a volume from a VTK image. The grid is resized to fit the loaded volume.
void MakeTriangles (void)
 Runs the Marching Tetrahedrons algorithm. The result is then available in triangles_. Each three consecutive entries in triangles_ represents one triangle.
bool Quit (void)
 In interactive sessions, this function returns true at any point after a user has pressed "q" or <ESC> in the render window.
virtual void Render (void)
 Render a virtual depth map. If interactive mode is true (see class SDF_Parameters) it will also display a preview window with estimated normal vectors.
virtual void SaveSDF (const std::string &filename=std::string("sdf_volume.vti"))
 Saves the current volume as a VTK image.
void SaveTriangles (const std::string filename=std::string("triangles.obj"))
 Dumps the zero level set as triangles to an OBJ file. SaveTriangles must be preceded by a call to MakeTriangles.
void SaveTrianglesSTL (const std::string filename=std::string("triangles.stl"))
 Dumps the zero level set as triangles to an STL file. This method also computes the triangles so there is no need to call MakeTriangles.
virtual double SDF (const Eigen::Vector4d &location)
 Returns the signed distance at the given location.
virtual double SDFGradient (const Eigen::Vector4d &location, int dim, int stepSize)
 Computes the gradient of the SDF at the location, along dimension dim, with central differences. stepSize chooses how far away from the central cell the samples should be taken before computing the difference.
 SDFTracker ()
 Constructor with default parameters.
 SDFTracker (SDF_Parameters &parameters)
 Constructor with custom parameters.
void SetCurrentTransformation (const Eigen::Matrix4d &T)
 sets the current transformation to the given matrix
cv::Point2d To2D (const Eigen::Vector4d &location, double fx, double fy, double cx, double cy)
 Finds the inverse projection of a 3D point to the image plane, given camera parameters.
Eigen::Vector4d To3D (int row, int column, double depth, double fx, double fy, double cx, double cy)
 Projects a depth map pixel into a 3D point, given camera parameters.
Eigen::Matrix4d Twist (const Vector6d &xi)
 Computes an antisymmetric matrix based on the pose change vector. To get a transformation matrix from this, you have to call Twist(xi).exp().
virtual void UpdateDepth (const cv::Mat &depth)
 Sets the current depth map.
virtual void UpdatePoints (const std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > &Points)
 Alternative to depth maps, sets the current point vector (x y z 1)
bool ValidGradient (const Eigen::Vector4d &location)
 Checks the validity of the gradient of the SDF at the current point.
virtual ~SDFTracker ()

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW
std::vector< Eigen::Vector4d > 
triangles_

Protected Member Functions

virtual void DeleteGrids (void)
virtual void Init (SDF_Parameters &parameters)
void MarchingTetrahedrons (Eigen::Vector4d &Origin, int tetrahedron)
Eigen::Vector4d VertexInterp (double iso, Eigen::Vector4d &p1d, Eigen::Vector4d &p2d, double valp1, double valp2)

Protected Attributes

std::string camera_name_
Vector6d cumulative_pose_
boost::mutex depth_mutex_
boost::mutex depthDenoised_mutex_
cv::Mat * depthImage_
cv::Mat * depthImage_denoised_
bool first_frame_
float *** myGrid_
SDF_Parameters parameters_
std::vector< Eigen::Vector4d,
Eigen::aligned_allocator
< Eigen::Vector4d > > 
Points_
boost::mutex points_mutex_
Vector6d Pose_
bool quit_
Eigen::Matrix4d Transformation_
boost::mutex transformation_mutex_
std::vector< Eigen::Matrix4d,
Eigen::aligned_allocator
< Eigen::Matrix4d > > 
transformations_
bool ** validityMask_

Detailed Description

Definition at line 50 of file sdf_tracker.h.


Constructor & Destructor Documentation

Constructor with default parameters.

Definition at line 51 of file sdf_tracker.cpp.

Constructor with custom parameters.

Definition at line 56 of file sdf_tracker.cpp.

SDFTracker::~SDFTracker ( ) [virtual]

Definition at line 61 of file sdf_tracker.cpp.


Member Function Documentation

void SDFTracker::DeleteGrids ( void  ) [protected, virtual]

Definition at line 142 of file sdf_tracker.cpp.

Estimates the incremental pose change vector from the current pose, relative to the current depth map.

Definition at line 1138 of file sdf_tracker.cpp.

Estimates the incremental pose change vector from the current pose, relative to the current point vector.

Definition at line 1245 of file sdf_tracker.cpp.

void SDFTracker::FuseDepth ( void  ) [virtual]

Fuses the current depth map into the TSDF volume, the current depth map is set using UpdateDepth.

Definition at line 840 of file sdf_tracker.cpp.

void SDFTracker::FuseDepth ( const cv::Mat &  depth) [virtual]

Estimates the pose, fuses the given depth map and renders a virtual depth map (all in one)

Definition at line 1021 of file sdf_tracker.cpp.

void SDFTracker::FusePoints ( void  ) [virtual]

Fuses the current point vector into the TSDF volume, the current point vector is set using UpdatePoints.

Definition at line 901 of file sdf_tracker.cpp.

Eigen::Matrix4d SDFTracker::GetCurrentTransformation ( void  )

gets the current transformation matrix

Definition at line 1450 of file sdf_tracker.cpp.

void SDFTracker::GetDenoisedImage ( cv::Mat &  img)

gets the denoised image produced by Render.

Definition at line 1436 of file sdf_tracker.cpp.

void SDFTracker::Init ( SDF_Parameters parameters) [protected, virtual]

Definition at line 81 of file sdf_tracker.cpp.

void SDFTracker::LoadSDF ( const std::string &  filename) [virtual]

Loads a volume from a VTK image. The grid is resized to fit the loaded volume.

Definition at line 1524 of file sdf_tracker.cpp.

void SDFTracker::MakeTriangles ( void  )

Runs the Marching Tetrahedrons algorithm. The result is then available in triangles_. Each three consecutive entries in triangles_ represents one triangle.

Definition at line 159 of file sdf_tracker.cpp.

void SDFTracker::MarchingTetrahedrons ( Eigen::Vector4d &  Origin,
int  tetrahedron 
) [protected]

Definition at line 364 of file sdf_tracker.cpp.

bool SDFTracker::Quit ( void  )

In interactive sessions, this function returns true at any point after a user has pressed "q" or <ESC> in the render window.

Definition at line 1443 of file sdf_tracker.cpp.

void SDFTracker::Render ( void  ) [virtual]

Render a virtual depth map. If interactive mode is true (see class SDF_Parameters) it will also display a preview window with estimated normal vectors.

Definition at line 1347 of file sdf_tracker.cpp.

void SDFTracker::SaveSDF ( const std::string &  filename = std::string("sdf_volume.vti")) [virtual]

Saves the current volume as a VTK image.

Definition at line 1467 of file sdf_tracker.cpp.

void SDFTracker::SaveTriangles ( const std::string  filename = std::string("triangles.obj"))

Dumps the zero level set as triangles to an OBJ file. SaveTriangles must be preceded by a call to MakeTriangles.

Definition at line 180 of file sdf_tracker.cpp.

void SDFTracker::SaveTrianglesSTL ( const std::string  filename = std::string("triangles.stl"))

Dumps the zero level set as triangles to an STL file. This method also computes the triangles so there is no need to call MakeTriangles.

double SDFTracker::SDF ( const Eigen::Vector4d &  location) [virtual]

Returns the signed distance at the given location.

Definition at line 1108 of file sdf_tracker.cpp.

double SDFTracker::SDFGradient ( const Eigen::Vector4d &  location,
int  dim,
int  stepSize 
) [virtual]

Computes the gradient of the SDF at the location, along dimension dim, with central differences. stepSize chooses how far away from the central cell the samples should be taken before computing the difference.

Definition at line 354 of file sdf_tracker.cpp.

void SDFTracker::SetCurrentTransformation ( const Eigen::Matrix4d &  T)

sets the current transformation to the given matrix

Definition at line 1460 of file sdf_tracker.cpp.

cv::Point2d SDFTracker::To2D ( const Eigen::Vector4d &  location,
double  fx,
double  fy,
double  cx,
double  cy 
)

Finds the inverse projection of a 3D point to the image plane, given camera parameters.

Definition at line 259 of file sdf_tracker.cpp.

Eigen::Vector4d SDFTracker::To3D ( int  row,
int  column,
double  depth,
double  fx,
double  fy,
double  cx,
double  cy 
)

Projects a depth map pixel into a 3D point, given camera parameters.

Definition at line 248 of file sdf_tracker.cpp.

Eigen::Matrix4d SDFTracker::Twist ( const Vector6d xi)

Computes an antisymmetric matrix based on the pose change vector. To get a transformation matrix from this, you have to call Twist(xi).exp().

Definition at line 235 of file sdf_tracker.cpp.

void SDFTracker::UpdateDepth ( const cv::Mat &  depth) [virtual]

Sets the current depth map.

Definition at line 807 of file sdf_tracker.cpp.

void SDFTracker::UpdatePoints ( const std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > &  Points) [virtual]

Alternative to depth maps, sets the current point vector (x y z 1)

Definition at line 831 of file sdf_tracker.cpp.

bool SDFTracker::ValidGradient ( const Eigen::Vector4d &  location)

Checks the validity of the gradient of the SDF at the current point.

Definition at line 272 of file sdf_tracker.cpp.

Eigen::Vector4d SDFTracker::VertexInterp ( double  iso,
Eigen::Vector4d &  p1d,
Eigen::Vector4d &  p2d,
double  valp1,
double  valp2 
) [protected]

Definition at line 196 of file sdf_tracker.cpp.


Member Data Documentation

std::string SDFTracker::camera_name_ [protected]

Definition at line 67 of file sdf_tracker.h.

Definition at line 59 of file sdf_tracker.h.

Definition at line 64 of file sdf_tracker.h.

Definition at line 66 of file sdf_tracker.h.

cv::Mat* SDFTracker::depthImage_ [protected]

Definition at line 60 of file sdf_tracker.h.

cv::Mat* SDFTracker::depthImage_denoised_ [protected]

Definition at line 61 of file sdf_tracker.h.

bool SDFTracker::first_frame_ [protected]

Definition at line 71 of file sdf_tracker.h.

float*** SDFTracker::myGrid_ [protected]

Definition at line 70 of file sdf_tracker.h.

Definition at line 73 of file sdf_tracker.h.

std::vector<Eigen::Vector4d,Eigen::aligned_allocator<Eigen::Vector4d> > SDFTracker::Points_ [protected]

Definition at line 55 of file sdf_tracker.h.

Definition at line 65 of file sdf_tracker.h.

Definition at line 58 of file sdf_tracker.h.

bool SDFTracker::quit_ [protected]

Definition at line 72 of file sdf_tracker.h.

Eigen::Matrix4d SDFTracker::Transformation_ [protected]

Definition at line 57 of file sdf_tracker.h.

Definition at line 63 of file sdf_tracker.h.

std::vector<Eigen::Matrix4d,Eigen::aligned_allocator<Eigen::Matrix4d> > SDFTracker::transformations_ [protected]

Definition at line 54 of file sdf_tracker.h.

EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::vector<Eigen::Vector4d> SDFTracker::triangles_

Definition at line 83 of file sdf_tracker.h.

bool** SDFTracker::validityMask_ [protected]

Definition at line 69 of file sdf_tracker.h.


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


sdf_tracker
Author(s): danielcanelhas
autogenerated on Mon Jan 6 2014 11:32:02