Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
rtabmap::CameraMobile Class Reference

#include <CameraMobile.h>

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

Public Member Functions

void addEnvSensor (int type, float value)
 
 CameraMobile (bool smoothing=false)
 
virtual void close ()
 
const CameraModelgetCameraModel () const
 
const TransformgetDeviceTColorCamera () const
 
const cv::Mat & getOcclusionImage (CameraModel *model=0) const
 
const TransformgetOriginOffset () const
 
ScreenRotation getScreenRotation () const
 
virtual std::string getSerial () 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
 
void poseReceived (const Transform &pose)
 
void resetOrigin ()
 
void setData (const SensorData &data, const Transform &pose, const glm::mat4 &viewMatrix, const glm::mat4 &projectionMatrix, const float *texCoord)
 
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 spinOnce ()
 
bool uvsInitialized () const
 
const float * uvsTransformed () const
 
virtual ~CameraMobile ()
 
- Public Member Functions inherited from rtabmap::Camera
float getImageRate () const
 
const TransformgetLocalTransform () const
 
virtual bool getPose (double stamp, Transform &pose, cv::Mat &covariance)
 
bool initFromFile (const std::string &calibrationPath)
 
virtual bool odomProvided () const
 
void resetTimer ()
 
void setImageRate (float imageRate)
 
void setLocalTransform (const Transform &localTransform)
 
SensorData takeImage (CameraInfo *info=0)
 
virtual ~Camera ()
 
- Public Member Functions inherited from UThread
Handle getThreadHandle () const
 
unsigned long getThreadId () const
 
bool isCreating () const
 
bool isIdle () const
 
bool isKilled () const
 
bool isRunning () const
 
void join (bool killFirst=false)
 
void kill ()
 
void setAffinity (int cpu=0)
 
void setPriority (Priority priority)
 
void start ()
 
 UThread (Priority priority=kPNormal)
 
virtual ~UThread ()
 
- Public Member Functions inherited from UThreadC< void >
int Create (Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const
 
int Create (Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const
 
int Create (unsigned long &ThreadId, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const
 
int Create (unsigned long &ThreadId, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const
 
virtual ~UThreadC ()
 
virtual ~UThreadC ()
 
- Public Member Functions inherited from UEventsSender
 UEventsSender ()
 
virtual ~UEventsSender ()
 

Static Public Member Functions

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 Member Functions inherited from UThread
static unsigned long currentThreadId ()
 
- Static Public Member Functions inherited from UThreadC< void >
static int Create (const Handler &Function, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false)
 
static int Create (const Handler &Function, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false)
 
static int Detach (Handle H)
 
static int Detach (const Handle &H)
 
static int Join (const Handle &H)
 
static int Join (Handle H)
 
static int Kill (Handle H)
 
static int Kill (const Handle &H)
 

Static Public Attributes

static const float bilateralFilteringSigmaR = 0.075f
 
static const float bilateralFilteringSigmaS = 2.0f
 
static const rtabmap::Transform opticalRotation
 
static const rtabmap::Transform opticalRotationInv
 

Protected Member Functions

virtual SensorData captureImage (CameraInfo *info=0)
 
virtual void capturePoseOnly ()
 
virtual void mainLoop ()
 
virtual void mainLoopBegin ()
 
- Protected Member Functions inherited from rtabmap::Camera
 Camera (float imageRate=0, const Transform &localTransform=Transform::getIdentity())
 
int getNextSeqID ()
 
- Protected Member Functions inherited from UThreadC< void >
 UThreadC ()
 
 UThreadC ()
 
- Protected Member Functions inherited from UEventsSender
void post (UEvent *event, bool async=true) const
 

Protected Attributes

Transform deviceTColorCamera_
 
CameraModel model_
 
glm::mat4 projectionMatrix_
 
UTimer spinOnceFrameRateTimer_
 
double spinOncePreviousStamp_
 
GLuint textureId_
 
float transformed_uvs_ [8]
 
bool uvs_initialized_ = false
 
glm::mat4 viewMatrix_
 

Private Attributes

UTimer cameraStartedTime_
 
ScreenRotation colorCameraToDisplayRotation_
 
SensorData data_
 
EnvSensors lastEnvSensors_
 
GPS lastKnownGPS_
 
cv::Mat occlusionImage_
 
CameraModel occlusionModel_
 
Transform originOffset_
 
bool originUpdate_
 
Transform pose_
 
Transform previousPose_
 
double previousStamp_
 
bool smoothing_
 
double stampEpochOffset_
 

Additional Inherited Members

- Public Types inherited from UThread
enum  Priority {
  kPLow, kPBelowNormal, kPNormal, kPAboveNormal,
  kPRealTime
}
 
- Public Types inherited from UThreadC< void >
typedef THREAD_HANDLE Handle
 
typedef THREAD_HANDLE Handle
 
typedef void(* Handler) ()
 
typedef void(* Handler) ()
 
- Static Protected Member Functions inherited from UThreadC< void >
static void Exit ()
 
static void Exit ()
 
static Handle Self ()
 
static int Self ()
 
static void TestCancel ()
 
static void TestCancel ()
 

Detailed Description

Definition at line 71 of file CameraMobile.h.

Constructor & Destructor Documentation

◆ CameraMobile()

rtabmap::CameraMobile::CameraMobile ( bool  smoothing = false)

Definition at line 55 of file CameraMobile.cpp.

◆ ~CameraMobile()

rtabmap::CameraMobile::~CameraMobile ( )
virtual

Definition at line 69 of file CameraMobile.cpp.

Member Function Documentation

◆ addEnvSensor()

void rtabmap::CameraMobile::addEnvSensor ( int  type,
float  value 
)

Definition at line 198 of file CameraMobile.cpp.

◆ captureImage()

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

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

Implements rtabmap::Camera.

Reimplemented in rtabmap::CameraARCore, rtabmap::CameraTango, and rtabmap::CameraAREngine.

Definition at line 396 of file CameraMobile.cpp.

◆ capturePoseOnly()

virtual void rtabmap::CameraMobile::capturePoseOnly ( )
inlineprotectedvirtual

Reimplemented in rtabmap::CameraARCore, and rtabmap::CameraAREngine.

Definition at line 126 of file CameraMobile.h.

◆ close()

void rtabmap::CameraMobile::close ( )
virtual

Reimplemented in rtabmap::CameraARCore, rtabmap::CameraAREngine, and rtabmap::CameraTango.

Definition at line 80 of file CameraMobile.cpp.

◆ getCameraModel()

const CameraModel& rtabmap::CameraMobile::getCameraModel ( ) const
inline

Definition at line 105 of file CameraMobile.h.

◆ getDeviceTColorCamera()

const Transform& rtabmap::CameraMobile::getDeviceTColorCamera ( ) const
inline

Definition at line 106 of file CameraMobile.h.

◆ getOcclusionImage()

const cv::Mat& rtabmap::CameraMobile::getOcclusionImage ( CameraModel model = 0) const
inline

Definition at line 122 of file CameraMobile.h.

◆ getOriginOffset()

const Transform& rtabmap::CameraMobile::getOriginOffset ( ) const
inline

Definition at line 99 of file CameraMobile.h.

◆ getScreenRotation()

ScreenRotation rtabmap::CameraMobile::getScreenRotation ( ) const
inline

Definition at line 119 of file CameraMobile.h.

◆ getSerial()

virtual std::string rtabmap::CameraMobile::getSerial ( ) const
inlinevirtual

Implements rtabmap::Camera.

Reimplemented in rtabmap::CameraARCore, rtabmap::CameraAREngine, and rtabmap::CameraTango.

Definition at line 97 of file CameraMobile.h.

◆ getTextureId()

GLuint rtabmap::CameraMobile::getTextureId ( )
inline

Definition at line 115 of file CameraMobile.h.

◆ getVPMatrices()

void rtabmap::CameraMobile::getVPMatrices ( glm::mat4 view,
glm::mat4 projection 
) const
inline

Definition at line 118 of file CameraMobile.h.

◆ init()

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

Implements rtabmap::Camera.

Reimplemented in rtabmap::CameraARCore, rtabmap::CameraAREngine, and rtabmap::CameraTango.

Definition at line 74 of file CameraMobile.cpp.

◆ isCalibrated()

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

Implements rtabmap::Camera.

Definition at line 132 of file CameraMobile.cpp.

◆ mainLoop()

void rtabmap::CameraMobile::mainLoop ( )
protectedvirtual

Pure virtual method mainLoop(). The inner loop of the thread. This method is called repetitively until the thread is killed. Note that if kill() is called in mainLoopBegin(), mainLoop() is not called, terminating immediately the thread.

See also
mainLoop()
kill()

Implements UThread.

Definition at line 242 of file CameraMobile.cpp.

◆ mainLoopBegin()

void rtabmap::CameraMobile::mainLoopBegin ( )
protectedvirtual

Virtual method mainLoopBegin(). User can implement this function to add a behavior before the main loop is started. It is called once (before entering mainLoop()).

Reimplemented from UThread.

Definition at line 233 of file CameraMobile.cpp.

◆ poseReceived()

void rtabmap::CameraMobile::poseReceived ( const Transform pose)

Definition at line 109 of file CameraMobile.cpp.

◆ resetOrigin()

void rtabmap::CameraMobile::resetOrigin ( )

Definition at line 98 of file CameraMobile.cpp.

◆ 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

Definition at line 405 of file CameraMobile.cpp.

◆ setData()

void rtabmap::CameraMobile::setData ( const SensorData data,
const Transform pose,
const glm::mat4 viewMatrix,
const glm::mat4 projectionMatrix,
const float *  texCoord 
)

Definition at line 142 of file CameraMobile.cpp.

◆ setGPS()

void rtabmap::CameraMobile::setGPS ( const GPS gps)

Definition at line 137 of file CameraMobile.cpp.

◆ setOcclusionImage()

void rtabmap::CameraMobile::setOcclusionImage ( const cv::Mat &  image,
const CameraModel model 
)
inline

Definition at line 121 of file CameraMobile.h.

◆ setScreenRotationAndSize()

virtual void rtabmap::CameraMobile::setScreenRotationAndSize ( ScreenRotation  colorCameraToDisplayRotation,
int  width,
int  height 
)
inlinevirtual

Reimplemented in rtabmap::CameraARCore.

Definition at line 108 of file CameraMobile.h.

◆ setSmoothing()

void rtabmap::CameraMobile::setSmoothing ( bool  enabled)
inline

Definition at line 107 of file CameraMobile.h.

◆ spinOnce()

void rtabmap::CameraMobile::spinOnce ( )

Definition at line 203 of file CameraMobile.cpp.

◆ uvsInitialized()

bool rtabmap::CameraMobile::uvsInitialized ( ) const
inline

Definition at line 116 of file CameraMobile.h.

◆ uvsTransformed()

const float* rtabmap::CameraMobile::uvsTransformed ( ) const
inline

Definition at line 117 of file CameraMobile.h.

Member Data Documentation

◆ bilateralFilteringSigmaR

const float rtabmap::CameraMobile::bilateralFilteringSigmaR = 0.075f
static

Definition at line 74 of file CameraMobile.h.

◆ bilateralFilteringSigmaS

const float rtabmap::CameraMobile::bilateralFilteringSigmaS = 2.0f
static

Definition at line 73 of file CameraMobile.h.

◆ cameraStartedTime_

UTimer rtabmap::CameraMobile::cameraStartedTime_
private

Definition at line 146 of file CameraMobile.h.

◆ colorCameraToDisplayRotation_

ScreenRotation rtabmap::CameraMobile::colorCameraToDisplayRotation_
private

Definition at line 149 of file CameraMobile.h.

◆ data_

SensorData rtabmap::CameraMobile::data_
private

Definition at line 155 of file CameraMobile.h.

◆ deviceTColorCamera_

Transform rtabmap::CameraMobile::deviceTColorCamera_
protected

Definition at line 133 of file CameraMobile.h.

◆ lastEnvSensors_

EnvSensors rtabmap::CameraMobile::lastEnvSensors_
private

Definition at line 151 of file CameraMobile.h.

◆ lastKnownGPS_

GPS rtabmap::CameraMobile::lastKnownGPS_
private

Definition at line 150 of file CameraMobile.h.

◆ model_

CameraModel rtabmap::CameraMobile::model_
protected

Definition at line 132 of file CameraMobile.h.

◆ occlusionImage_

cv::Mat rtabmap::CameraMobile::occlusionImage_
private

Definition at line 158 of file CameraMobile.h.

◆ occlusionModel_

CameraModel rtabmap::CameraMobile::occlusionModel_
private

Definition at line 159 of file CameraMobile.h.

◆ opticalRotation

const rtabmap::Transform rtabmap::CameraMobile::opticalRotation
static
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

const rtabmap::Transform rtabmap::CameraMobile::opticalRotationInv
static
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

Definition at line 152 of file CameraMobile.h.

◆ originUpdate_

bool rtabmap::CameraMobile::originUpdate_
private

Definition at line 153 of file CameraMobile.h.

◆ pose_

Transform rtabmap::CameraMobile::pose_
private

Definition at line 156 of file CameraMobile.h.

◆ previousPose_

Transform rtabmap::CameraMobile::previousPose_
private

Definition at line 144 of file CameraMobile.h.

◆ previousStamp_

double rtabmap::CameraMobile::previousStamp_
private

Definition at line 145 of file CameraMobile.h.

◆ projectionMatrix_

glm::mat4 rtabmap::CameraMobile::projectionMatrix_
protected

Definition at line 139 of file CameraMobile.h.

◆ smoothing_

bool rtabmap::CameraMobile::smoothing_
private

Definition at line 148 of file CameraMobile.h.

◆ spinOnceFrameRateTimer_

UTimer rtabmap::CameraMobile::spinOnceFrameRateTimer_
protected

Definition at line 134 of file CameraMobile.h.

◆ spinOncePreviousStamp_

double rtabmap::CameraMobile::spinOncePreviousStamp_
protected

Definition at line 135 of file CameraMobile.h.

◆ stampEpochOffset_

double rtabmap::CameraMobile::stampEpochOffset_
private

Definition at line 147 of file CameraMobile.h.

◆ textureId_

GLuint rtabmap::CameraMobile::textureId_
protected

Definition at line 137 of file CameraMobile.h.

◆ transformed_uvs_

float rtabmap::CameraMobile::transformed_uvs_[8]
protected

Definition at line 140 of file CameraMobile.h.

◆ uvs_initialized_

bool rtabmap::CameraMobile::uvs_initialized_ = false
protected

Definition at line 141 of file CameraMobile.h.

◆ viewMatrix_

glm::mat4 rtabmap::CameraMobile::viewMatrix_
protected

Definition at line 138 of file CameraMobile.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:39:00