#include <CameraMobile.h>
|
void | addEnvSensor (int type, float value) |
|
| CameraMobile (bool smoothing=false) |
|
virtual void | close () |
|
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 |
|
virtual std::string | getSerial () const |
|
double | getStampEpochOffset () const |
|
GLuint | getTextureId () |
|
void | getVPMatrices (glm::mat4 &view, glm::mat4 &projection) const |
|
virtual bool | init (const std::string &calibrationFolder=".", const std::string &cameraName="") |
|
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 () |
|
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 |
|
void | resetTimer () |
|
void | setFrameRate (float frameRate) |
|
void | setLocalTransform (const Transform &localTransform) |
|
SensorData | takeData (SensorCaptureInfo *info=0) |
|
virtual | ~SensorCapture () |
|
| UEventsSender () |
|
virtual | ~UEventsSender () |
|
Definition at line 71 of file CameraMobile.h.
◆ CameraMobile()
rtabmap::CameraMobile::CameraMobile |
( |
bool |
smoothing = false | ) |
|
◆ ~CameraMobile()
rtabmap::CameraMobile::~CameraMobile |
( |
| ) |
|
|
virtual |
◆ addEnvSensor()
void rtabmap::CameraMobile::addEnvSensor |
( |
int |
type, |
|
|
float |
value |
|
) |
| |
◆ captureImage()
◆ close()
void rtabmap::CameraMobile::close |
( |
| ) |
|
|
virtual |
◆ getCameraModel()
const CameraModel& rtabmap::CameraMobile::getCameraModel |
( |
| ) |
const |
|
inline |
◆ getDeviceTColorCamera()
const Transform& rtabmap::CameraMobile::getDeviceTColorCamera |
( |
| ) |
const |
|
inline |
◆ getOcclusionImage()
◆ getOriginOffset()
const Transform& rtabmap::CameraMobile::getOriginOffset |
( |
| ) |
const |
|
inline |
◆ getPose()
bool rtabmap::CameraMobile::getPose |
( |
double |
epochStamp, |
|
|
Transform & |
pose, |
|
|
cv::Mat & |
covariance, |
|
|
double |
maxWaitTime = 0.06 |
|
) |
| |
|
virtual |
◆ getScreenRotation()
◆ getSerial()
virtual std::string rtabmap::CameraMobile::getSerial |
( |
| ) |
const |
|
inlinevirtual |
◆ getStampEpochOffset()
double rtabmap::CameraMobile::getStampEpochOffset |
( |
| ) |
const |
|
inline |
◆ getTextureId()
GLuint rtabmap::CameraMobile::getTextureId |
( |
| ) |
|
|
inline |
◆ getVPMatrices()
void rtabmap::CameraMobile::getVPMatrices |
( |
glm::mat4 & |
view, |
|
|
glm::mat4 & |
projection |
|
) |
| const |
|
inline |
◆ init()
bool rtabmap::CameraMobile::init |
( |
const std::string & |
calibrationFolder = "." , |
|
|
const std::string & |
cameraName = "" |
|
) |
| |
|
virtual |
◆ isCalibrated()
bool rtabmap::CameraMobile::isCalibrated |
( |
| ) |
const |
|
virtual |
◆ odomProvided()
virtual bool rtabmap::CameraMobile::odomProvided |
( |
| ) |
const |
|
inlinevirtual |
◆ poseReceived()
void rtabmap::CameraMobile::poseReceived |
( |
const Transform & |
pose, |
|
|
double |
deviceStamp |
|
) |
| |
◆ postUpdate()
void rtabmap::CameraMobile::postUpdate |
( |
| ) |
|
|
private |
◆ resetOrigin()
void rtabmap::CameraMobile::resetOrigin |
( |
| ) |
|
◆ scanFromPointCloudData()
LaserScan rtabmap::CameraMobile::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 |
◆ setGPS()
void rtabmap::CameraMobile::setGPS |
( |
const GPS & |
gps | ) |
|
◆ setOcclusionImage()
void rtabmap::CameraMobile::setOcclusionImage |
( |
const cv::Mat & |
image, |
|
|
const CameraModel & |
model |
|
) |
| |
|
inline |
◆ setScreenRotationAndSize()
virtual void rtabmap::CameraMobile::setScreenRotationAndSize |
( |
ScreenRotation |
colorCameraToDisplayRotation, |
|
|
int |
width, |
|
|
int |
height |
|
) |
| |
|
inlinevirtual |
◆ setSmoothing()
void rtabmap::CameraMobile::setSmoothing |
( |
bool |
enabled | ) |
|
|
inline |
◆ update()
◆ updateDataOnRender()
◆ updateOnRender()
void rtabmap::CameraMobile::updateOnRender |
( |
| ) |
|
◆ uvsInitialized()
bool rtabmap::CameraMobile::uvsInitialized |
( |
| ) |
const |
|
inline |
◆ uvsTransformed()
const float* rtabmap::CameraMobile::uvsTransformed |
( |
| ) |
const |
|
inline |
◆ bilateralFilteringSigmaR
const float rtabmap::CameraMobile::bilateralFilteringSigmaR = 0.075f |
|
static |
◆ bilateralFilteringSigmaS
const float rtabmap::CameraMobile::bilateralFilteringSigmaS = 2.0f |
|
static |
◆ colorCameraToDisplayRotation_
◆ data_
◆ dataMutex_
UMutex rtabmap::CameraMobile::dataMutex_ |
|
private |
◆ dataPose_
◆ dataReady_
◆ deviceTColorCamera_
Transform rtabmap::CameraMobile::deviceTColorCamera_ |
|
protected |
◆ firstFrame_
bool rtabmap::CameraMobile::firstFrame_ |
|
private |
◆ lastEnvSensors_
◆ lastKnownGPS_
GPS rtabmap::CameraMobile::lastKnownGPS_ |
|
private |
◆ model_
◆ occlusionImage_
cv::Mat rtabmap::CameraMobile::occlusionImage_ |
|
private |
◆ occlusionModel_
◆ opticalRotation
Initial value:= Transform(
0.0f, 0.0f, 1.0f, 0.0f,
-1.0f, 0.0f, 0.0f, 0.0f,
0.0f, -1.0f, 0.0f, 0.0f)
Definition at line 76 of file CameraMobile.h.
◆ opticalRotationInv
Initial value:= Transform(
0.0f, -1.0f, 0.0f, 0.0f,
0.0f, 0.0f, -1.0f, 0.0f,
1.0f, 0.0f, 0.0f, 0.0f)
Definition at line 77 of file CameraMobile.h.
◆ originOffset_
Transform rtabmap::CameraMobile::originOffset_ |
|
private |
◆ originUpdate_
bool rtabmap::CameraMobile::originUpdate_ |
|
private |
◆ poseBuffer_
std::map<double, Transform> rtabmap::CameraMobile::poseBuffer_ |
|
private |
◆ poseMutex_
UMutex rtabmap::CameraMobile::poseMutex_ |
|
private |
◆ projectionMatrix_
glm::mat4 rtabmap::CameraMobile::projectionMatrix_ |
|
protected |
◆ smoothing_
bool rtabmap::CameraMobile::smoothing_ |
|
private |
◆ stampEpochOffset_
double rtabmap::CameraMobile::stampEpochOffset_ |
|
private |
◆ textureId_
GLuint rtabmap::CameraMobile::textureId_ |
|
protected |
◆ transformed_uvs_
float rtabmap::CameraMobile::transformed_uvs_[8] |
|
protected |
◆ uvs_initialized_
bool rtabmap::CameraMobile::uvs_initialized_ = false |
|
protected |
◆ viewMatrix_
The documentation for this class was generated from the following files: