Public Types | Public Member Functions | Protected Member Functions | Private Attributes
clams::FrameProjector Class Reference

#include <frame_projector.h>

List of all members.

Public Types

typedef std::vector
< std::vector< std::vector
< double > > > 
RangeIndex

Public Member Functions

RangeIndex cloudToRangeIndex (const pcl::PointCloud< pcl::PointXYZ >::Ptr &pcd) const
cv::Mat estimateMapDepth (const pcl::PointCloud< pcl::PointXYZ >::Ptr &map, const rtabmap::Transform &transform, const cv::Mat &measurement, double coneRadius=0.02, double coneStdevThresh=0.03) const
 FrameProjector (const rtabmap::CameraModel &model)
pcl::PointXYZ project (const ProjectivePoint &ppt) const
ProjectivePoint reproject (const pcl::PointXYZ &pt) const

Protected Member Functions

bool coneFit (const cv::Size &imageSize, const RangeIndex &rindex, int uc, int vc, double radius, double measurement_depth, double *mean, double *stdev) const

Private Attributes

rtabmap::CameraModel model_

Detailed Description

This is essentially a pinhole camera model for an RGBD sensor, with some extra functions added on for use during calibration.

Definition at line 63 of file frame_projector.h.


Member Typedef Documentation

typedef std::vector< std::vector< std::vector<double> > > clams::FrameProjector::RangeIndex

Definition at line 67 of file frame_projector.h.


Constructor & Destructor Documentation

Definition at line 42 of file frame_projector.cpp.


Member Function Documentation

FrameProjector::RangeIndex clams::FrameProjector::cloudToRangeIndex ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  pcd) const

Definition at line 49 of file frame_projector.cpp.

bool clams::FrameProjector::coneFit ( const cv::Size &  imageSize,
const RangeIndex rindex,
int  uc,
int  vc,
double  radius,
double  measurement_depth,
double *  mean,
double *  stdev 
) const [protected]

Definition at line 175 of file frame_projector.cpp.

cv::Mat clams::FrameProjector::estimateMapDepth ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  map,
const rtabmap::Transform transform,
const cv::Mat &  measurement,
double  coneRadius = 0.02,
double  coneStdevThresh = 0.03 
) const

transform is applied to the map, then projected into a depth index. The best depth estimate from the map corresponding to the measurement depth frame will be returned.

Definition at line 105 of file frame_projector.cpp.

pcl::PointXYZ clams::FrameProjector::project ( const ProjectivePoint ppt) const

Definition at line 80 of file frame_projector.cpp.

ProjectivePoint clams::FrameProjector::reproject ( const pcl::PointXYZ &  pt) const

Definition at line 90 of file frame_projector.cpp.


Member Data Documentation

Definition at line 91 of file frame_projector.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:40