Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Private Member Functions
rtabmap::CameraK4W2 Class Reference

#include <CameraRGBD.h>

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

List of all members.

Public Types

enum  Type { kTypeColor2DepthSD, kTypeDepth2ColorSD, kTypeDepth2ColorHD }

Public Member Functions

 CameraK4W2 (int deviceId=0, Type type=kTypeDepth2ColorSD, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity())
virtual std::string getSerial () const
virtual bool init (const std::string &calibrationFolder=".", const std::string &cameraName="")
virtual bool isCalibrated () const
virtual ~CameraK4W2 ()

Static Public Member Functions

static bool available ()

Static Public Attributes

static const int cColorHeight = 1080
static const int cColorWidth = 1920
static const int cDepthHeight = 424
static const int cDepthWidth = 512

Protected Member Functions

virtual SensorData captureImage (CameraInfo *info=0)

Private Member Functions

void close ()

Detailed Description

Definition at line 323 of file CameraRGBD.h.


Member Enumeration Documentation

Enumerator:
kTypeColor2DepthSD 
kTypeDepth2ColorSD 
kTypeDepth2ColorHD 

Definition at line 329 of file CameraRGBD.h.


Constructor & Destructor Documentation

rtabmap::CameraK4W2::CameraK4W2 ( int  deviceId = 0,
Type  type = kTypeDepth2ColorSD,
float  imageRate = 0.0f,
const Transform localTransform = Transform::getIdentity() 
)

Definition at line 2074 of file CameraRGBD.cpp.

Definition at line 2094 of file CameraRGBD.cpp.


Member Function Documentation

bool rtabmap::CameraK4W2::available ( ) [static]

Definition at line 2065 of file CameraRGBD.cpp.

SensorData rtabmap::CameraK4W2::captureImage ( CameraInfo info = 0) [protected, virtual]

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

Implements rtabmap::Camera.

Definition at line 2293 of file CameraRGBD.cpp.

void rtabmap::CameraK4W2::close ( ) [private]

Definition at line 2119 of file CameraRGBD.cpp.

std::string rtabmap::CameraK4W2::getSerial ( ) const [virtual]

Implements rtabmap::Camera.

Definition at line 2275 of file CameraRGBD.cpp.

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

Implements rtabmap::Camera.

Definition at line 2147 of file CameraRGBD.cpp.

bool rtabmap::CameraK4W2::isCalibrated ( ) const [virtual]

Implements rtabmap::Camera.

Definition at line 2270 of file CameraRGBD.cpp.


Member Data Documentation

const int rtabmap::CameraK4W2::cColorHeight = 1080 [static]

Definition at line 339 of file CameraRGBD.h.

const int rtabmap::CameraK4W2::cColorWidth = 1920 [static]

Definition at line 338 of file CameraRGBD.h.

const int rtabmap::CameraK4W2::cDepthHeight = 424 [static]

Definition at line 337 of file CameraRGBD.h.

const int rtabmap::CameraK4W2::cDepthWidth = 512 [static]

Definition at line 336 of file CameraRGBD.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:41