#include <CameraARCore.h>

Public Member Functions | |
| CameraARCore (void *env, void *context, void *activity, bool depthFromMotion=false, bool smoothing=false) | |
| virtual void | close () |
| const cv::Mat & | getOcclusionImage (CameraModel *model=0) const |
| 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 () |
| void | updateOcclusionImage (bool enabled) |
| 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 CameraModel & | getCameraModel () const |
| const Transform & | getDeviceTColorCamera () const |
| const Transform & | getOriginOffset () const |
| virtual bool | isCalibrated () const |
| void | poseReceived (const Transform &pose) |
| void | resetOrigin () |
| void | setData (const SensorData &data, const Transform &pose) |
| void | setGPS (const GPS &gps) |
| void | setSmoothing (bool enabled) |
| void | spinOnce () |
| virtual | ~CameraMobile () |
Public Member Functions inherited from rtabmap::Camera | |
| float | getImageRate () const |
| const Transform & | getLocalTransform () const |
| 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 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=CameraModel::opticalRotation()) | |
| 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_ |
| cv::Mat | occlusionImage_ |
| CameraModel | occlusionModel_ |
| glm::mat4 | projectionMatrix_ |
| GLuint | textureId_ |
| float | transformed_uvs_ [BackgroundRenderer::kNumVertices *2] |
| bool | updateOcclusionImage_ |
| bool | uvs_initialized_ = false |
| glm::mat4 | viewMatrix_ |
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_ |
| UTimer | spinOnceFrameRateTimer_ |
| double | spinOncePreviousStamp_ |
Definition at line 51 of file CameraARCore.h.
| rtabmap::CameraARCore::CameraARCore | ( | void * | env, |
| void * | context, | ||
| void * | activity, | ||
| bool | depthFromMotion = false, |
||
| bool | smoothing = false |
||
| ) |
Definition at line 40 of file CameraARCore.cpp.
|
virtual |
Definition at line 53 of file CameraARCore.cpp.
|
protectedvirtual |
returned rgb and depth images should be already rectified if calibration was loaded
Reimplemented from rtabmap::CameraMobile.
Definition at line 347 of file CameraARCore.cpp.
|
protectedvirtual |
Reimplemented from rtabmap::CameraMobile.
Definition at line 572 of file CameraARCore.cpp.
|
virtual |
Reimplemented from rtabmap::CameraMobile.
Definition at line 248 of file CameraARCore.cpp.
|
inline |
Definition at line 71 of file CameraARCore.h.
|
private |
|
virtual |
Reimplemented from rtabmap::CameraMobile.
Definition at line 128 of file CameraARCore.cpp.
|
inline |
Definition at line 79 of file CameraARCore.h.
Definition at line 68 of file CameraARCore.h.
| void rtabmap::CameraARCore::imageCallback | ( | AImageReader * | reader | ) |
|
virtual |
Sets the behavior of ArSession_update(). See ::ArUpdateMode for available options.
Reimplemented from rtabmap::CameraMobile.
Definition at line 133 of file CameraARCore.cpp.
|
static |
Definition at line 285 of file CameraARCore.cpp.
|
virtual |
Reimplemented from rtabmap::CameraMobile.
Definition at line 333 of file CameraARCore.cpp.
| void rtabmap::CameraARCore::setupGL | ( | ) |
|
inline |
Definition at line 70 of file CameraARCore.h.
|
inline |
Definition at line 66 of file CameraARCore.h.
|
inline |
Definition at line 67 of file CameraARCore.h.
|
private |
Definition at line 93 of file CameraARCore.h.
|
private |
Definition at line 97 of file CameraARCore.h.
|
private |
Definition at line 95 of file CameraARCore.h.
|
private |
Definition at line 96 of file CameraARCore.h.
|
private |
Definition at line 99 of file CameraARCore.h.
|
private |
Definition at line 98 of file CameraARCore.h.
|
private |
Definition at line 94 of file CameraARCore.h.
|
private |
Definition at line 101 of file CameraARCore.h.
|
private |
Definition at line 92 of file CameraARCore.h.
|
private |
Definition at line 111 of file CameraARCore.h.
|
private |
Definition at line 91 of file CameraARCore.h.
|
private |
Definition at line 109 of file CameraARCore.h.
|
private |
Definition at line 110 of file CameraARCore.h.
|
private |
Definition at line 106 of file CameraARCore.h.
|
private |
Definition at line 100 of file CameraARCore.h.
|
private |
Definition at line 103 of file CameraARCore.h.
|
private |
Definition at line 108 of file CameraARCore.h.
|
private |
Definition at line 104 of file CameraARCore.h.
|
private |
Definition at line 105 of file CameraARCore.h.