#include <CameraMyntEye.h>
|
| CameraMyntEye (const std::string &device="", bool apiRectification=false, bool apiDepth=false, 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 |
|
virtual bool | odomProvided () const |
|
void | publishInterIMU (bool enabled) |
|
void | setAutoExposure () |
|
void | setIrControl (int value) |
|
void | setManualExposure (int gain=24, int brightness=120, int constrast=116) |
|
virtual | ~CameraMyntEye () |
|
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 () |
|
float | getFrameRate () const |
|
const Transform & | getLocalTransform () const |
|
virtual bool | getPose (double stamp, Transform &pose, cv::Mat &covariance, double maxWaitTime=0.06) |
|
void | resetTimer () |
|
void | setFrameRate (float frameRate) |
|
void | setLocalTransform (const Transform &localTransform) |
|
SensorData | takeData (SensorCaptureInfo *info=0) |
|
virtual | ~SensorCapture () |
|
◆ CameraMyntEye()
◆ ~CameraMyntEye()
rtabmap::CameraMyntEye::~CameraMyntEye |
( |
| ) |
|
|
virtual |
◆ available()
bool rtabmap::CameraMyntEye::available |
( |
| ) |
|
|
static |
◆ captureImage()
◆ getSerial()
std::string rtabmap::CameraMyntEye::getSerial |
( |
| ) |
const |
|
virtual |
◆ init()
bool rtabmap::CameraMyntEye::init |
( |
const std::string & |
calibrationFolder = "." , |
|
|
const std::string & |
cameraName = "" |
|
) |
| |
|
virtual |
◆ isCalibrated()
bool rtabmap::CameraMyntEye::isCalibrated |
( |
| ) |
const |
|
virtual |
◆ odomProvided()
virtual bool rtabmap::CameraMyntEye::odomProvided |
( |
| ) |
const |
|
inlinevirtual |
◆ publishInterIMU()
void rtabmap::CameraMyntEye::publishInterIMU |
( |
bool |
enabled | ) |
|
◆ setAutoExposure()
void rtabmap::CameraMyntEye::setAutoExposure |
( |
| ) |
|
◆ setIrControl()
void rtabmap::CameraMyntEye::setIrControl |
( |
int |
value | ) |
|
◆ setManualExposure()
void rtabmap::CameraMyntEye::setManualExposure |
( |
int |
gain = 24 , |
|
|
int |
brightness = 120 , |
|
|
int |
constrast = 116 |
|
) |
| |
The documentation for this class was generated from the following files: