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 TransformgetOriginOffset () const
 
virtual std::string getSerial () 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)
 
void setGPS (const GPS &gps)
 
virtual void setScreenRotationAndSize (ScreenRotation colorCameraToDisplayRotation, int width, int height)
 
void setSmoothing (bool enabled)
 
void spinOnce ()
 
virtual ~CameraMobile ()
 
- Public Member Functions inherited from rtabmap::Camera
float getImageRate () const
 
const TransformgetLocalTransform () 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 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=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
 

Protected Attributes

Transform deviceTColorCamera_
 
CameraModel model_
 
UTimer spinOnceFrameRateTimer_
 
double spinOncePreviousStamp_
 

Private Attributes

UTimer cameraStartedTime_
 
ScreenRotation colorCameraToDisplayRotation_
 
SensorData data_
 
EnvSensors lastEnvSensors_
 
GPS lastKnownGPS_
 
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 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 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

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

Definition at line 54 of file CameraMobile.cpp.

rtabmap::CameraMobile::~CameraMobile ( )
virtual

Definition at line 66 of file CameraMobile.cpp.

Member Function Documentation

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

Definition at line 134 of file CameraMobile.cpp.

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 332 of file CameraMobile.cpp.

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

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

Definition at line 106 of file CameraMobile.h.

void rtabmap::CameraMobile::close ( )
virtual

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

Definition at line 77 of file CameraMobile.cpp.

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

Definition at line 94 of file CameraMobile.h.

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

Definition at line 95 of file CameraMobile.h.

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

Definition at line 88 of file CameraMobile.h.

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

Implements rtabmap::Camera.

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

Definition at line 86 of file CameraMobile.h.

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 71 of file CameraMobile.cpp.

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

Implements rtabmap::Camera.

Definition at line 117 of file CameraMobile.cpp.

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 178 of file CameraMobile.cpp.

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 169 of file CameraMobile.cpp.

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

Definition at line 94 of file CameraMobile.cpp.

void rtabmap::CameraMobile::resetOrigin ( )

Definition at line 89 of file CameraMobile.cpp.

void rtabmap::CameraMobile::setData ( const SensorData data,
const Transform pose 
)

Definition at line 127 of file CameraMobile.cpp.

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

Definition at line 122 of file CameraMobile.cpp.

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

Reimplemented in rtabmap::CameraARCore.

Definition at line 97 of file CameraMobile.h.

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

Definition at line 96 of file CameraMobile.h.

void rtabmap::CameraMobile::spinOnce ( )

Definition at line 139 of file CameraMobile.cpp.

Member Data Documentation

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

Definition at line 74 of file CameraMobile.h.

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

Definition at line 73 of file CameraMobile.h.

UTimer rtabmap::CameraMobile::cameraStartedTime_
private

Definition at line 120 of file CameraMobile.h.

ScreenRotation rtabmap::CameraMobile::colorCameraToDisplayRotation_
private

Definition at line 123 of file CameraMobile.h.

SensorData rtabmap::CameraMobile::data_
private

Definition at line 129 of file CameraMobile.h.

Transform rtabmap::CameraMobile::deviceTColorCamera_
protected

Definition at line 113 of file CameraMobile.h.

EnvSensors rtabmap::CameraMobile::lastEnvSensors_
private

Definition at line 125 of file CameraMobile.h.

GPS rtabmap::CameraMobile::lastKnownGPS_
private

Definition at line 124 of file CameraMobile.h.

CameraModel rtabmap::CameraMobile::model_
protected

Definition at line 112 of file CameraMobile.h.

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.

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.

Transform rtabmap::CameraMobile::originOffset_
private

Definition at line 126 of file CameraMobile.h.

bool rtabmap::CameraMobile::originUpdate_
private

Definition at line 127 of file CameraMobile.h.

Transform rtabmap::CameraMobile::pose_
private

Definition at line 130 of file CameraMobile.h.

Transform rtabmap::CameraMobile::previousPose_
private

Definition at line 118 of file CameraMobile.h.

double rtabmap::CameraMobile::previousStamp_
private

Definition at line 119 of file CameraMobile.h.

bool rtabmap::CameraMobile::smoothing_
private

Definition at line 122 of file CameraMobile.h.

UTimer rtabmap::CameraMobile::spinOnceFrameRateTimer_
protected

Definition at line 114 of file CameraMobile.h.

double rtabmap::CameraMobile::spinOncePreviousStamp_
protected

Definition at line 115 of file CameraMobile.h.

double rtabmap::CameraMobile::stampEpochOffset_
private

Definition at line 121 of file CameraMobile.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:08