#include <CameraK4W2.h>

Public Types | |
| enum | Type { kTypeColor2DepthSD, kTypeDepth2ColorSD, kTypeDepth2ColorHD } |
Public Member Functions | |
| CameraK4W2 (int deviceId=0, Type type=kTypeDepth2ColorSD, float imageRate=0.0f, const Transform &localTransform=CameraModel::opticalRotation()) | |
| virtual std::string | getSerial () const |
| virtual bool | init (const std::string &calibrationFolder=".", const std::string &cameraName="") |
| virtual bool | isCalibrated () const |
| virtual | ~CameraK4W2 () |
Public Member Functions inherited from rtabmap::Camera | |
| float | getImageRate () const |
| const Transform & | getLocalTransform () const |
| bool | initFromFile (const std::string &calibrationPath) |
| 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 () |
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) |
Protected Member Functions inherited from rtabmap::Camera | |
| Camera (float imageRate=0, const Transform &localTransform=CameraModel::opticalRotation()) | |
| int | getNextSeqID () |
Private Member Functions | |
| void | close () |
Definition at line 46 of file CameraK4W2.h.
| Enumerator | |
|---|---|
| kTypeColor2DepthSD | |
| kTypeDepth2ColorSD | |
| kTypeDepth2ColorHD | |
Definition at line 52 of file CameraK4W2.h.
| rtabmap::CameraK4W2::CameraK4W2 | ( | int | deviceId = 0, |
| Type | type = kTypeDepth2ColorSD, |
||
| float | imageRate = 0.0f, |
||
| const Transform & | localTransform = CameraModel::opticalRotation() |
||
| ) |
Definition at line 62 of file CameraK4W2.cpp.
|
virtual |
Definition at line 82 of file CameraK4W2.cpp.
|
static |
Definition at line 53 of file CameraK4W2.cpp.
|
protectedvirtual |
returned rgb and depth images should be already rectified if calibration was loaded
Implements rtabmap::Camera.
Definition at line 281 of file CameraK4W2.cpp.
|
private |
Definition at line 107 of file CameraK4W2.cpp.
|
virtual |
Implements rtabmap::Camera.
Definition at line 263 of file CameraK4W2.cpp.
|
virtual |
Implements rtabmap::Camera.
Definition at line 135 of file CameraK4W2.cpp.
|
virtual |
Implements rtabmap::Camera.
Definition at line 258 of file CameraK4W2.cpp.
|
static |
Definition at line 62 of file CameraK4W2.h.
|
static |
Definition at line 61 of file CameraK4W2.h.
|
static |
Definition at line 60 of file CameraK4W2.h.
|
static |
Definition at line 59 of file CameraK4W2.h.