#include <CameraTango.h>
Public Member Functions | |
CameraTango (bool colorCamera, int decimation, bool publishRawScan, bool smoothing) | |
virtual void | close () |
void | cloudReceived (const cv::Mat &cloud, double timestamp) |
virtual std::string | getSerial () const |
virtual bool | init (const std::string &calibrationFolder=".", const std::string &cameraName="") |
void | rgbReceived (const cv::Mat &tangoImage, int type, double timestamp) |
void | setDecimation (int value) |
void | setRawScanPublished (bool enabled) |
void | tangoEventReceived (int type, const char *key, const char *value) |
rtabmap::Transform | tangoPoseToTransform (const TangoPoseData *tangoPose) const |
virtual | ~CameraTango () |
Public Member Functions inherited from rtabmap::CameraMobile | |
void | addEnvSensor (int type, float value) |
CameraMobile (bool smoothing=false) | |
const CameraModel & | getCameraModel () const |
const Transform & | getDeviceTColorCamera () const |
const cv::Mat & | getOcclusionImage (CameraModel *model=0) const |
const Transform & | getOriginOffset () const |
virtual bool | getPose (double epochStamp, Transform &pose, cv::Mat &covariance, double maxWaitTime=0.06) |
ScreenRotation | getScreenRotation () const |
double | getStampEpochOffset () const |
GLuint | getTextureId () |
void | getVPMatrices (glm::mat4 &view, glm::mat4 &projection) const |
virtual bool | isCalibrated () const |
virtual bool | odomProvided () const |
void | poseReceived (const Transform &pose, double deviceStamp) |
void | resetOrigin () |
void | setGPS (const GPS &gps) |
void | setOcclusionImage (const cv::Mat &image, const CameraModel &model) |
virtual void | setScreenRotationAndSize (ScreenRotation colorCameraToDisplayRotation, int width, int height) |
void | setSmoothing (bool enabled) |
void | update (const SensorData &data, const Transform &pose, const glm::mat4 &viewMatrix, const glm::mat4 &projectionMatrix, const float *texCoord) |
void | updateOnRender () |
bool | uvsInitialized () const |
const float * | uvsTransformed () const |
virtual | ~CameraMobile () |
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 |
void | resetTimer () |
void | setFrameRate (float frameRate) |
void | setLocalTransform (const Transform &localTransform) |
SensorData | takeData (SensorCaptureInfo *info=0) |
virtual | ~SensorCapture () |
Public Member Functions inherited from UEventsSender | |
UEventsSender () | |
virtual | ~UEventsSender () |
Protected Member Functions | |
virtual SensorData | updateDataOnRender (Transform &pose) |
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()) | |
Protected Member Functions inherited from UEventsSender | |
void | post (UEvent *event, bool async=true) const |
Private Member Functions | |
rtabmap::Transform | getPoseAtTimestamp (double timestamp) |
Private Attributes | |
bool | colorCamera_ |
int | decimation_ |
cv::Mat | fisheyeRectifyMapX_ |
cv::Mat | fisheyeRectifyMapY_ |
bool | rawScanPublished_ |
void * | tango_config_ |
cv::Mat | tangoColor_ |
double | tangoColorStamp_ |
int | tangoColorType_ |
SensorData | tangoData_ |
boost::mutex | tangoDataMutex_ |
USemaphore | tangoDataReady_ |
Additional Inherited Members | |
Static Public Member Functions inherited from rtabmap::CameraMobile | |
static LaserScan | scanFromPointCloudData (const cv::Mat &pointCloudData, int points, const Transform &pose, const CameraModel &model, const cv::Mat &rgb, std::vector< cv::KeyPoint > *kpts=0, std::vector< cv::Point3f > *kpts3D=0, int kptsSize=3) |
Static Public Attributes inherited from rtabmap::CameraMobile | |
static const float | bilateralFilteringSigmaR = 0.075f |
static const float | bilateralFilteringSigmaS = 2.0f |
static const rtabmap::Transform | opticalRotation |
static const rtabmap::Transform | opticalRotationInv |
Protected Attributes inherited from rtabmap::CameraMobile | |
Transform | deviceTColorCamera_ |
CameraModel | model_ |
glm::mat4 | projectionMatrix_ |
GLuint | textureId_ |
float | transformed_uvs_ [8] |
bool | uvs_initialized_ = false |
glm::mat4 | viewMatrix_ |
Definition at line 46 of file CameraTango.h.
rtabmap::CameraTango::CameraTango | ( | bool | colorCamera, |
int | decimation, | ||
bool | publishRawScan, | ||
bool | smoothing | ||
) |
Definition at line 117 of file CameraTango.cpp.
|
virtual |
Definition at line 129 of file CameraTango.cpp.
|
virtual |
Reimplemented from rtabmap::CameraMobile.
Definition at line 424 of file CameraTango.cpp.
void rtabmap::CameraTango::cloudReceived | ( | const cv::Mat & | cloud, |
double | timestamp | ||
) |
Definition at line 440 of file CameraTango.cpp.
|
private |
Definition at line 747 of file CameraTango.cpp.
|
virtual |
Reimplemented from rtabmap::CameraMobile.
Definition at line 725 of file CameraTango.cpp.
|
virtual |
Reimplemented from rtabmap::CameraMobile.
Definition at line 193 of file CameraTango.cpp.
Definition at line 706 of file CameraTango.cpp.
|
inline |
Definition at line 55 of file CameraTango.h.
|
inline |
Definition at line 56 of file CameraTango.h.
void rtabmap::CameraTango::tangoEventReceived | ( | int | type, |
const char * | key, | ||
const char * | value | ||
) |
Definition at line 720 of file CameraTango.cpp.
rtabmap::Transform rtabmap::CameraTango::tangoPoseToTransform | ( | const TangoPoseData * | tangoPose | ) | const |
Definition at line 730 of file CameraTango.cpp.
|
protectedvirtual |
Reimplemented from rtabmap::CameraMobile.
Definition at line 778 of file CameraTango.cpp.
|
private |
Definition at line 70 of file CameraTango.h.
|
private |
Definition at line 71 of file CameraTango.h.
|
private |
Definition at line 79 of file CameraTango.h.
|
private |
Definition at line 80 of file CameraTango.h.
|
private |
Definition at line 72 of file CameraTango.h.
|
private |
Definition at line 69 of file CameraTango.h.
|
private |
Definition at line 74 of file CameraTango.h.
|
private |
Definition at line 76 of file CameraTango.h.
|
private |
Definition at line 75 of file CameraTango.h.
|
private |
Definition at line 73 of file CameraTango.h.
|
private |
Definition at line 77 of file CameraTango.h.
|
private |
Definition at line 78 of file CameraTango.h.