#include <CameraOpenNI2.h>
Public Types | |
enum | Type { kTypeColorDepth, kTypeIRDepth, kTypeIR } |
Public Member Functions | |
CameraOpenNI2 (const std::string &deviceId="", Type type=kTypeColorDepth, float imageRate=0, 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 |
bool | setAutoExposure (bool enabled) |
bool | setAutoWhiteBalance (bool enabled) |
void | setDepthDecimation (int decimation) |
bool | setExposure (int value) |
bool | setGain (int value) |
void | setIRDepthShift (int horizontal, int vertical) |
bool | setMirroring (bool enabled) |
void | setOpenNI2StampsAndIDsUsed (bool used) |
virtual | ~CameraOpenNI2 () |
Public Member Functions inherited from rtabmap::Camera | |
float | getImageRate () const |
bool | initFromFile (const std::string &calibrationPath) |
bool | isInterIMUPublishing () const |
void | setImageRate (float imageRate) |
void | setInterIMUPublishing (bool enabled, IMUFilter *filter=0) |
SensorData | takeImage (SensorCaptureInfo *info=0) |
virtual | ~Camera () |
Public Member Functions inherited from rtabmap::SensorCapture | |
float | getFrameRate () const |
const Transform & | getLocalTransform () const |
virtual bool | getPose (double stamp, Transform &pose, cv::Mat &covariance, double maxWaitTime=0.06) |
virtual bool | odomProvided () const |
void | resetTimer () |
void | setFrameRate (float frameRate) |
void | setLocalTransform (const Transform &localTransform) |
SensorData | takeData (SensorCaptureInfo *info=0) |
virtual | ~SensorCapture () |
Static Public Member Functions | |
static bool | available () |
static bool | exposureGainAvailable () |
Protected Member Functions | |
virtual SensorData | captureImage (SensorCaptureInfo *info=0) |
Protected Member Functions inherited from rtabmap::Camera | |
Camera (float imageRate=0, const Transform &localTransform=Transform::getIdentity()) | |
void | postInterIMU (const IMU &imu, double stamp) |
Protected Member Functions inherited from rtabmap::SensorCapture | |
int | getNextSeqID () |
SensorCapture (float frameRate=0, const Transform &localTransform=Transform::getIdentity()) | |
Definition at line 42 of file CameraOpenNI2.h.
Enumerator | |
---|---|
kTypeColorDepth | |
kTypeIRDepth | |
kTypeIR |
Definition at line 49 of file CameraOpenNI2.h.
rtabmap::CameraOpenNI2::CameraOpenNI2 | ( | const std::string & | deviceId = "" , |
Type | type = kTypeColorDepth , |
||
float | imageRate = 0 , |
||
const Transform & | localTransform = Transform::getIdentity() |
||
) |
Definition at line 60 of file CameraOpenNI2.cpp.
|
virtual |
Definition at line 83 of file CameraOpenNI2.cpp.
|
static |
Definition at line 42 of file CameraOpenNI2.cpp.
|
protectedvirtual |
Implements rtabmap::Camera.
Definition at line 476 of file CameraOpenNI2.cpp.
|
static |
Definition at line 51 of file CameraOpenNI2.cpp.
|
virtual |
Implements rtabmap::SensorCapture.
Definition at line 465 of file CameraOpenNI2.cpp.
|
virtual |
Implements rtabmap::SensorCapture.
Definition at line 194 of file CameraOpenNI2.cpp.
|
virtual |
Implements rtabmap::Camera.
Definition at line 460 of file CameraOpenNI2.cpp.
bool rtabmap::CameraOpenNI2::setAutoExposure | ( | bool | enabled | ) |
Definition at line 112 of file CameraOpenNI2.cpp.
bool rtabmap::CameraOpenNI2::setAutoWhiteBalance | ( | bool | enabled | ) |
Definition at line 99 of file CameraOpenNI2.cpp.
void rtabmap::CameraOpenNI2::setDepthDecimation | ( | int | decimation | ) |
Definition at line 186 of file CameraOpenNI2.cpp.
bool rtabmap::CameraOpenNI2::setExposure | ( | int | value | ) |
Definition at line 125 of file CameraOpenNI2.cpp.
bool rtabmap::CameraOpenNI2::setGain | ( | int | value | ) |
Definition at line 142 of file CameraOpenNI2.cpp.
Definition at line 178 of file CameraOpenNI2.cpp.
bool rtabmap::CameraOpenNI2::setMirroring | ( | bool | enabled | ) |
Definition at line 159 of file CameraOpenNI2.cpp.
void rtabmap::CameraOpenNI2::setOpenNI2StampsAndIDsUsed | ( | bool | used | ) |
Definition at line 171 of file CameraOpenNI2.cpp.