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

#include <CameraARCore.h>

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

Public Member Functions

 CameraARCore (void *env, void *context, void *activity, bool depthFromMotion=false, bool smoothing=false)
 
virtual void close ()
 
virtual std::string getSerial () const
 
GLuint getTextureId () const
 
void getVPMatrices (glm::mat4 &view, glm::mat4 &projection) const
 
void imageCallback (AImageReader *reader)
 
virtual bool init (const std::string &calibrationFolder=".", const std::string &cameraName="")
 
virtual void setScreenRotationAndSize (ScreenRotation colorCameraToDisplayRotation, int width, int height)
 
void setupGL ()
 
bool uvsInitialized () const
 
const float * uvsTransformed () const
 
virtual ~CameraARCore ()
 
- Public Member Functions inherited from rtabmap::CameraMobile
void addEnvSensor (int type, float value)
 
 CameraMobile (bool smoothing=false)
 
const CameraModelgetCameraModel () const
 
const TransformgetDeviceTColorCamera () const
 
const cv::Mat & getOcclusionImage (CameraModel *model=0) const
 
const TransformgetOriginOffset () const
 
ScreenRotation getScreenRotation () const
 
GLuint getTextureId ()
 
void getVPMatrices (glm::mat4 &view, glm::mat4 &projection) const
 
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)
 
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 float *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)
 
- 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 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)
 

Protected Member Functions

virtual SensorData captureImage (CameraInfo *info=0)
 
virtual void capturePoseOnly ()
 
- Protected Member Functions inherited from rtabmap::CameraMobile
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
 

Private Member Functions

rtabmap::Transform getPoseAtTimestamp (double timestamp)
 

Private Attributes

void * activity_
 
ArCameraIntrinsics * arCameraIntrinsics_ = nullptr
 
ArConfig * arConfig_ = nullptr
 
ArFrame * arFrame_ = nullptr
 
bool arInstallRequested_
 
ArPose * arPose_ = nullptr
 
ArSession * arSession_ = nullptr
 
UMutex arSessionMutex_
 
void * context_
 
bool depthFromMotion_
 
void * env_
 

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 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
 
- 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 ()
 
- Protected Attributes inherited from rtabmap::CameraMobile
Transform deviceTColorCamera_
 
CameraModel model_
 
glm::mat4 projectionMatrix_
 
UTimer spinOnceFrameRateTimer_
 
double spinOncePreviousStamp_
 
GLuint textureId_
 
float transformed_uvs_ [8]
 
bool uvs_initialized_ = false
 
glm::mat4 viewMatrix_
 

Detailed Description

Definition at line 51 of file CameraARCore.h.

Constructor & Destructor Documentation

◆ CameraARCore()

rtabmap::CameraARCore::CameraARCore ( void *  env,
void *  context,
void *  activity,
bool  depthFromMotion = false,
bool  smoothing = false 
)

Definition at line 40 of file CameraARCore.cpp.

◆ ~CameraARCore()

rtabmap::CameraARCore::~CameraARCore ( )
virtual

Definition at line 50 of file CameraARCore.cpp.

Member Function Documentation

◆ captureImage()

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

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

Reimplemented from rtabmap::CameraMobile.

Definition at line 337 of file CameraARCore.cpp.

◆ capturePoseOnly()

void rtabmap::CameraARCore::capturePoseOnly ( )
protectedvirtual

Reimplemented from rtabmap::CameraMobile.

Definition at line 577 of file CameraARCore.cpp.

◆ close()

void rtabmap::CameraARCore::close ( )
virtual

Reimplemented from rtabmap::CameraMobile.

Definition at line 239 of file CameraARCore.cpp.

◆ getPoseAtTimestamp()

rtabmap::Transform rtabmap::CameraARCore::getPoseAtTimestamp ( double  timestamp)
private

◆ getSerial()

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

Reimplemented from rtabmap::CameraMobile.

Definition at line 119 of file CameraARCore.cpp.

◆ getTextureId()

GLuint rtabmap::CameraARCore::getTextureId ( ) const
inline

Definition at line 76 of file CameraARCore.h.

◆ getVPMatrices()

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

Definition at line 68 of file CameraARCore.h.

◆ imageCallback()

void rtabmap::CameraARCore::imageCallback ( AImageReader *  reader)

◆ init()

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

Sets the behavior of ArSession_update(). See ::ArUpdateMode for available options.

Reimplemented from rtabmap::CameraMobile.

Definition at line 124 of file CameraARCore.cpp.

◆ scanFromPointCloudData()

LaserScan rtabmap::CameraARCore::scanFromPointCloudData ( const float *  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 
)
static

Definition at line 275 of file CameraARCore.cpp.

◆ setScreenRotationAndSize()

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

Reimplemented from rtabmap::CameraMobile.

Definition at line 323 of file CameraARCore.cpp.

◆ setupGL()

void rtabmap::CameraARCore::setupGL ( )

◆ uvsInitialized()

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

Definition at line 66 of file CameraARCore.h.

◆ uvsTransformed()

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

Definition at line 67 of file CameraARCore.h.

Member Data Documentation

◆ activity_

void* rtabmap::CameraARCore::activity_
private

Definition at line 90 of file CameraARCore.h.

◆ arCameraIntrinsics_

ArCameraIntrinsics* rtabmap::CameraARCore::arCameraIntrinsics_ = nullptr
private

Definition at line 94 of file CameraARCore.h.

◆ arConfig_

ArConfig* rtabmap::CameraARCore::arConfig_ = nullptr
private

Definition at line 92 of file CameraARCore.h.

◆ arFrame_

ArFrame* rtabmap::CameraARCore::arFrame_ = nullptr
private

Definition at line 93 of file CameraARCore.h.

◆ arInstallRequested_

bool rtabmap::CameraARCore::arInstallRequested_
private

Definition at line 96 of file CameraARCore.h.

◆ arPose_

ArPose* rtabmap::CameraARCore::arPose_ = nullptr
private

Definition at line 95 of file CameraARCore.h.

◆ arSession_

ArSession* rtabmap::CameraARCore::arSession_ = nullptr
private

Definition at line 91 of file CameraARCore.h.

◆ arSessionMutex_

UMutex rtabmap::CameraARCore::arSessionMutex_
private

Definition at line 97 of file CameraARCore.h.

◆ context_

void* rtabmap::CameraARCore::context_
private

Definition at line 89 of file CameraARCore.h.

◆ depthFromMotion_

bool rtabmap::CameraARCore::depthFromMotion_
private

Definition at line 99 of file CameraARCore.h.

◆ env_

void* rtabmap::CameraARCore::env_
private

Definition at line 88 of file CameraARCore.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