Public Member Functions | Static Public Member Functions | Protected Member Functions | List of all members
rtabmap::CameraRealSense2 Class Reference

#include <CameraRealSense2.h>

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

Public Member Functions

 CameraRealSense2 (const std::string &deviceId="", float imageRate=0, 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
 
bool odomProvided () const
 
void publishInterIMU (bool enabled)
 
void setDualMode (bool enabled, const Transform &extrinsics)
 
void setEmitterEnabled (bool enabled)
 
void setGlobalTimeSync (bool enabled)
 
void setImagesRectified (bool enabled)
 
void setIRFormat (bool enabled, bool useDepthInsteadOfRightImage)
 
void setJsonConfig (const std::string &json)
 
void setOdomProvided (bool enabled)
 
void setResolution (int width, int height, int fps=30)
 
virtual ~CameraRealSense2 ()
 
- Public Member Functions inherited from rtabmap::Camera
float getImageRate () const
 
const TransformgetLocalTransform () const
 
bool initFromFile (const std::string &calibrationPath)
 
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 ()
 

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 ()
 

Detailed Description

Definition at line 55 of file CameraRealSense2.h.

Constructor & Destructor Documentation

rtabmap::CameraRealSense2::CameraRealSense2 ( const std::string &  deviceId = "",
float  imageRate = 0,
const Transform localTransform = CameraModel::opticalRotation() 
)

Definition at line 54 of file CameraRealSense2.cpp.

rtabmap::CameraRealSense2::~CameraRealSense2 ( )
virtual

Definition at line 90 of file CameraRealSense2.cpp.

Member Function Documentation

bool rtabmap::CameraRealSense2::available ( )
static

Definition at line 45 of file CameraRealSense2.cpp.

SensorData rtabmap::CameraRealSense2::captureImage ( CameraInfo info = 0)
protectedvirtual

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

Implements rtabmap::Camera.

Definition at line 1189 of file CameraRealSense2.cpp.

std::string rtabmap::CameraRealSense2::getSerial ( ) const
virtual

Implements rtabmap::Camera.

Definition at line 1092 of file CameraRealSense2.cpp.

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

Implements rtabmap::Camera.

Definition at line 470 of file CameraRealSense2.cpp.

bool rtabmap::CameraRealSense2::isCalibrated ( ) const
virtual

Implements rtabmap::Camera.

Definition at line 1083 of file CameraRealSense2.cpp.

bool rtabmap::CameraRealSense2::odomProvided ( ) const
virtual

Reimplemented from rtabmap::Camera.

Definition at line 1103 of file CameraRealSense2.cpp.

void rtabmap::CameraRealSense2::publishInterIMU ( bool  enabled)

Definition at line 1143 of file CameraRealSense2.cpp.

void rtabmap::CameraRealSense2::setDualMode ( bool  enabled,
const Transform extrinsics 
)

Definition at line 1150 of file CameraRealSense2.cpp.

void rtabmap::CameraRealSense2::setEmitterEnabled ( bool  enabled)

Definition at line 1112 of file CameraRealSense2.cpp.

void rtabmap::CameraRealSense2::setGlobalTimeSync ( bool  enabled)

Definition at line 1136 of file CameraRealSense2.cpp.

void rtabmap::CameraRealSense2::setImagesRectified ( bool  enabled)

Definition at line 1170 of file CameraRealSense2.cpp.

void rtabmap::CameraRealSense2::setIRFormat ( bool  enabled,
bool  useDepthInsteadOfRightImage 
)

Definition at line 1119 of file CameraRealSense2.cpp.

void rtabmap::CameraRealSense2::setJsonConfig ( const std::string &  json)

Definition at line 1163 of file CameraRealSense2.cpp.

void rtabmap::CameraRealSense2::setOdomProvided ( bool  enabled)

Definition at line 1177 of file CameraRealSense2.cpp.

void rtabmap::CameraRealSense2::setResolution ( int  width,
int  height,
int  fps = 30 
)

Definition at line 1127 of file CameraRealSense2.cpp.


The documentation for this class was generated from the following files:


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:08