Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | List of all members
rtabmap::CameraFreenect2 Class Reference

#include <CameraRGBD.h>

Inheritance diagram for rtabmap::CameraFreenect2:
Inheritance graph
[legend]

Public Types

enum  Type {
  kTypeColor2DepthSD, kTypeDepth2ColorSD, kTypeDepth2ColorHD, kTypeDepth2ColorHD2,
  kTypeIRDepth, kTypeColorIR
}
 

Public Member Functions

 CameraFreenect2 (int deviceId=0, Type type=kTypeDepth2ColorSD, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity(), float minDepth=0.3f, float maxDepth=12.0f, bool bilateralFiltering=true, bool edgeAwareFiltering=true, bool noiseFiltering=true, const std::string &pipelineName="")
 
virtual std::string getSerial () const
 
virtual bool init (const std::string &calibrationFolder=".", const std::string &cameraName="")
 
virtual bool isCalibrated () const
 
virtual ~CameraFreenect2 ()
 
- Public Member Functions inherited from rtabmap::Camera
float getImageRate () const
 
const TransformgetLocalTransform () const
 
virtual bool odomProvided () const
 
void resetTimer ()
 
void setImageRate (float imageRate)
 
void setLocalTransform (const Transform &localTransform)
 
SensorData takeImage (CameraInfo *info=0)
 
virtual ~Camera ()
 

Static Public Member Functions

static bool available ()
 

Protected Member Functions

virtual SensorData captureImage (CameraInfo *info=0)
 
- Protected Member Functions inherited from rtabmap::Camera
 Camera (float imageRate=0, const Transform &localTransform=Transform::getIdentity())
 
int getNextSeqID ()
 

Detailed Description

Definition at line 265 of file CameraRGBD.h.

Member Enumeration Documentation

Enumerator
kTypeColor2DepthSD 
kTypeDepth2ColorSD 
kTypeDepth2ColorHD 
kTypeDepth2ColorHD2 
kTypeIRDepth 
kTypeColorIR 

Definition at line 271 of file CameraRGBD.h.

Constructor & Destructor Documentation

rtabmap::CameraFreenect2::CameraFreenect2 ( int  deviceId = 0,
Type  type = kTypeDepth2ColorSD,
float  imageRate = 0.0f,
const Transform localTransform = Transform::getIdentity(),
float  minDepth = 0.3f,
float  maxDepth = 12.0f,
bool  bilateralFiltering = true,
bool  edgeAwareFiltering = true,
bool  noiseFiltering = true,
const std::string &  pipelineName = "" 
)

Definition at line 1371 of file CameraRGBD.cpp.

rtabmap::CameraFreenect2::~CameraFreenect2 ( )
virtual

Definition at line 1420 of file CameraRGBD.cpp.

Member Function Documentation

bool rtabmap::CameraFreenect2::available ( )
static

Definition at line 1362 of file CameraRGBD.cpp.

SensorData rtabmap::CameraFreenect2::captureImage ( CameraInfo info = 0)
protectedvirtual

returned rgb and depth images should be already rectified if calibration was loaded

Implements rtabmap::Camera.

Definition at line 1654 of file CameraRGBD.cpp.

std::string rtabmap::CameraFreenect2::getSerial ( ) const
virtual

Implements rtabmap::Camera.

Definition at line 1643 of file CameraRGBD.cpp.

bool rtabmap::CameraFreenect2::init ( const std::string &  calibrationFolder = ".",
const std::string &  cameraName = "" 
)
virtual

Implements rtabmap::Camera.

Definition at line 1505 of file CameraRGBD.cpp.

bool rtabmap::CameraFreenect2::isCalibrated ( ) const
virtual

Implements rtabmap::Camera.

Definition at line 1638 of file CameraRGBD.cpp.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:42