#include <CameraRGBD.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=Transform::getIdentity()) | |
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 |
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=Transform::getIdentity()) | |
int | getNextSeqID () |
Private Member Functions | |
void | close () |
Definition at line 323 of file CameraRGBD.h.
Enumerator | |
---|---|
kTypeColor2DepthSD | |
kTypeDepth2ColorSD | |
kTypeDepth2ColorHD |
Definition at line 329 of file CameraRGBD.h.
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.
|
virtual |
Definition at line 2094 of file CameraRGBD.cpp.
|
static |
Definition at line 2065 of file CameraRGBD.cpp.
|
protectedvirtual |
returned rgb and depth images should be already rectified if calibration was loaded
Implements rtabmap::Camera.
Definition at line 2293 of file CameraRGBD.cpp.
|
private |
Definition at line 2119 of file CameraRGBD.cpp.
|
virtual |
Implements rtabmap::Camera.
Definition at line 2275 of file CameraRGBD.cpp.
|
virtual |
Implements rtabmap::Camera.
Definition at line 2147 of file CameraRGBD.cpp.
|
virtual |
Implements rtabmap::Camera.
Definition at line 2270 of file CameraRGBD.cpp.
|
static |
Definition at line 339 of file CameraRGBD.h.
|
static |
Definition at line 338 of file CameraRGBD.h.
|
static |
Definition at line 337 of file CameraRGBD.h.
|
static |
Definition at line 336 of file CameraRGBD.h.