Public Member Functions | Private Member Functions | Private Attributes | List of all members
ipa_CameraSensors::VirtualRangeCam Class Reference

#include <VirtualRangeCam.h>

Inheritance diagram for ipa_CameraSensors::VirtualRangeCam:
Inheritance graph
[legend]

Public Member Functions

unsigned long AcquireImages (int widthStepRange, int widthStepGray, int widthStepCartesian, char *rangeImage=NULL, char *intensityImage=NULL, char *cartesianImage=NULL, bool getLatestFrame=true, bool undistort=true, ipa_CameraSensors::t_ToFGrayImageType grayImageType=ipa_CameraSensors::INTENSITY_32F1)
 
unsigned long AcquireImages (cv::Mat *rangeImage=0, cv::Mat *intensityImage=0, cv::Mat *cartesianImage=0, bool getLatestFrame=true, bool undistort=true, ipa_CameraSensors::t_ToFGrayImageType grayImageType=ipa_CameraSensors::INTENSITY_32F1)
 
unsigned long Close ()
 
unsigned long GetCalibratedUV (double x, double y, double z, double &u, double &v)
 
int GetNumberOfImages ()
 
unsigned long GetProperty (t_cameraProperty *cameraProperty)
 
unsigned long Init (std::string directory, int cameraIndex=0)
 
bool isInitialized ()
 
bool isOpen ()
 
unsigned long Open ()
 
unsigned long SaveParameters (const char *filename)
 
unsigned long SetPathToImages (std::string path)
 
unsigned long SetProperty (t_cameraProperty *cameraProperty)
 
unsigned long SetPropertyDefaults ()
 
 VirtualRangeCam ()
 
 ~VirtualRangeCam ()
 
- Public Member Functions inherited from ipa_CameraSensors::AbstractRangeImagingSensor
virtual t_CalibrationMethod GetCalibrationMethod ()
 
virtual t_cameraType GetCameraType ()
 
virtual unsigned long SetIntrinsics (cv::Mat &intrinsicMatrix, cv::Mat &undistortMapX, cv::Mat &undistortMapY)
 
virtual ~AbstractRangeImagingSensor ()
 Destructor. More...
 

Private Member Functions

void FindSourceImageFormat (std::map< std::string, int >::iterator &itCounter, std::string &ext)
 
unsigned long GetCalibratedXYMatlab (int u, int v, float z, float &x, float &y)
 
unsigned long GetCalibratedZMatlab (int u, int v, float zRaw, float &zCalibrated)
 
unsigned long LoadParameters (const char *filename, int cameraIndex)
 
void UpdateImageDimensionsOnFirstImage (std::string filename, std::string ext=".xml")
 

Private Attributes

std::vector< std::string > m_AmplitudeImageFileNames
 
std::string m_CameraDataDirectory
 Directory where the image data resides. More...
 
int m_CameraIndex
 Index of the specified camera. Important, when several cameras of the same type are present. More...
 
cv::Mat m_CoeffsA0
 a0 z-calibration parameters. One matrix entry corresponds to one pixel More...
 
cv::Mat m_CoeffsA1
 a1 z-calibration parameters. One matrix entry corresponds to one pixel More...
 
cv::Mat m_CoeffsA2
 a2 z-calibration parameters. One matrix entry corresponds to one pixel More...
 
cv::Mat m_CoeffsA3
 a3 z-calibration parameters. One matrix entry corresponds to one pixel More...
 
cv::Mat m_CoeffsA4
 a4 z-calibration parameters. One matrix entry corresponds to one pixel More...
 
cv::Mat m_CoeffsA5
 a5 z-calibration parameters. One matrix entry corresponds to one pixel More...
 
cv::Mat m_CoeffsA6
 a6 z-calibration parameters. One matrix entry corresponds to one pixel More...
 
bool m_CoeffsInitialized
 
std::vector< std::string > m_CoordinateImageFileNames
 
int m_ImageHeight
 Image height. More...
 
int m_ImageWidth
 Image width. More...
 
std::vector< std::string > m_IntensityImageFileNames
 
double m_k1
 
double m_k2
 
double m_p1
 
double m_p2
 Distortion parameters. More...
 
std::vector< std::string > m_RangeImageFileNames
 

Additional Inherited Members

- Public Attributes inherited from ipa_CameraSensors::AbstractRangeImagingSensor
unsigned int m_ImageCounter
 Holds the index of the image that is extracted during the next call of AcquireImages More...
 
- Protected Attributes inherited from ipa_CameraSensors::AbstractRangeImagingSensor
unsigned int m_BufferSize
 Number of images, the camera buffers internally. More...
 
t_CalibrationMethod m_CalibrationMethod
 Calibration method MATLAB, MATLAB_NO_Z or SWISSRANGER. More...
 
t_cameraType m_CameraType
 Camera Type. More...
 
bool m_initialized
 True, when the camera has sucessfully been initialized. More...
 
cv::Mat m_intrinsicMatrix
 Intrinsic parameters [fx 0 cx; 0 fy cy; 0 0 1]. More...
 
bool m_open
 True, when the camera has sucessfully been opend. More...
 
t_RangeCameraParameters m_RangeCameraParameters
 Storage for xml configuration file parmeters. More...
 
cv::Mat m_undistortMapX
 The output array of x coordinates for the undistortion map. More...
 
cv::Mat m_undistortMapY
 The output array of Y coordinates for the undistortion map. More...
 

Detailed Description

Interface class to virtual range camera like Swissranger 3000/4000. The class offers an interface to a virtual range camera, that is equal to the interface of a real range camera. However, pictures are read from a directory instead of the camera.

Definition at line 50 of file VirtualRangeCam.h.

Constructor & Destructor Documentation

VirtualRangeCam::VirtualRangeCam ( )

Definition at line 40 of file VirtualRangeCam.cpp.

VirtualRangeCam::~VirtualRangeCam ( )

Definition at line 51 of file VirtualRangeCam.cpp.

Member Function Documentation

unsigned long VirtualRangeCam::AcquireImages ( int  widthStepRange,
int  widthStepGray,
int  widthStepCartesian,
char *  rangeImage = NULL,
char *  grayImage = NULL,
char *  cartesianImage = NULL,
bool  getLatestFrame = true,
bool  undistort = true,
ipa_CameraSensors::t_ToFGrayImageType  grayImageType = ipa_CameraSensors::INTENSITY_32F1 
)
virtual

Acquires an image from SwissRanger. This implementation is designated for people that do not use openCV image type.

Parameters
widthStepRangeThe stride of a row from the range image.
widthStepGrayThe stride of a row from the grayscale intensity image.
widthStepCartesianThe stride of a row from the cartesian image.
rangeImagecharacter array with depth information.
grayImagecharacter array with intensity (grayscale) information.
cartesianImagecharacter array with cartesian (x,y,z) information in meters.
getLatestFrameSet true to acquire a new image on calling instead of returning the one acquired last time
useCalibratedZCalibrate z values
grayImageTypeEither gray image data is filled with amplitude image or intensity image
Returns
Return code.






Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 539 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::AcquireImages ( cv::Mat *  rangeImage = 0,
cv::Mat *  intensityImage = 0,
cv::Mat *  cartesianImage = 0,
bool  getLatestFrame = true,
bool  undistort = true,
ipa_CameraSensors::t_ToFGrayImageType  grayImageType = ipa_CameraSensors::INTENSITY_32F1 
)
virtual

Acquires an image from SwissRanger camera. Data is read from the camera and put into a corresponding OpenCV cv::Mat data type. The cv::Mat are allocated on demand.

Parameters
rangeImageOpenCV conform image with depth information.
grayImageOpenCV conform image with grayscale information.
cartesianImageOpenCV conform image with cartesian (x,y,z) information in meters.
getLatestFrameSet true to acquire a new image on calling instead of returning the one acquired last time
useCalibratedZCalibrate z values
grayImageTypeEither gray image data is filled with amplitude image or intensity image
Exceptions
IPA_ExceptionThrows an exception, if camera access failed

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 496 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::Close ( )
virtual

Close camera device.

Returns
Return code.

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 431 of file VirtualRangeCam.cpp.

void VirtualRangeCam::FindSourceImageFormat ( std::map< std::string, int >::iterator &  itCounter,
std::string &  ext 
)
inlineprivate

Compares the value of the iterator with ext in order to find the extension which has instances in the directory. Throws an error if different file formats are present at the same time.

Parameters
itCounterIterator containing a file extension and a number of instances.
extIs empty if no extension was found before, otherwise it contains the found extension.

Definition at line 227 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::GetCalibratedUV ( double  x,
double  y,
double  z,
double &  u,
double &  v 
)

Definition at line 924 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::GetCalibratedXYMatlab ( int  u,
int  v,
float  z,
float &  x,
float &  y 
)
private

Definition at line 885 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::GetCalibratedZMatlab ( int  u,
int  v,
float  zRaw,
float &  zCalibrated 
)
private

Definition at line 873 of file VirtualRangeCam.cpp.

int VirtualRangeCam::GetNumberOfImages ( )
virtual

Returns the number of images in the directory

Returns
The number of images in the directory

Reimplemented from ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 839 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::GetProperty ( t_cameraProperty cameraProperty)
virtual

Function to set properties of the range imaging sensor.

Parameters
propertyIDThe ID of the property.
cameraPropertyThe value of the property.
Returns
Return code.

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 467 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::Init ( std::string  directory,
int  cameraIndex = 0 
)
virtual

Initializes Swissranger.

Parameters
directoryPath to the directory of the range imaging sensor parameter file.
cameraIndexIt is possible to have several cameras of the same type on the system. One may use the camera index to apply different configuration files to each of them.
Returns
Return code.

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 59 of file VirtualRangeCam.cpp.

bool ipa_CameraSensors::VirtualRangeCam::isInitialized ( )
inlinevirtual

Determines if range imaging camera has successfully been initialized.

Returns
True if camera is initialized, false otherwise.

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 81 of file VirtualRangeCam.h.

bool ipa_CameraSensors::VirtualRangeCam::isOpen ( )
inlinevirtual

Determines if range imaging camera camera has successfully been opened.

Returns
True if camera is open, false otherwise.

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 82 of file VirtualRangeCam.h.

unsigned long VirtualRangeCam::LoadParameters ( const char *  filename,
int  cameraIndex 
)
privatevirtual

Load general range camera parameters .

Parameters
filenameConfiguration file-path and file-name.
cameraIndexThe index of the camera within the configuration file i.e. SR_CAM_0 or SR_CAM_1
Returns
Return code

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 969 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::Open ( )
virtual

Opens the camera device. All camera specific parameters for opening the camera should have been set within the Init() function.

Returns
Return code.

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 242 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::SaveParameters ( const char *  filename)
virtual

Save camera parameters. Saves the on-line set parameters for the range imaging camera to a file.

Parameters
filenameConfiguration file name.
Returns
Return code.

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 865 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::SetPathToImages ( std::string  path)
virtual

Function specific to virtual camera. Resets the image directory read from the configuration file.

Parameters
pathThe camera path
Returns
Return code

Reimplemented from ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 859 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::SetProperty ( t_cameraProperty cameraProperty)
virtual

Function to set properties of the range imaging sensor.

Parameters
propertyIDThe ID of the property.
cameraPropertyThe value of the property.
Returns
Return code.

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 444 of file VirtualRangeCam.cpp.

unsigned long VirtualRangeCam::SetPropertyDefaults ( )
virtual

Function to set property defaults of the range imaging sensor.

Returns
Return code.

Implements ipa_CameraSensors::AbstractRangeImagingSensor.

Definition at line 461 of file VirtualRangeCam.cpp.

void VirtualRangeCam::UpdateImageDimensionsOnFirstImage ( std::string  filename,
std::string  ext = ".xml" 
)
inlineprivate

Reads out the image width and height from the first image found in the filesystem.

Parameters
filenameThe name of that image.

Definition at line 205 of file VirtualRangeCam.cpp.

Member Data Documentation

std::vector<std::string> ipa_CameraSensors::VirtualRangeCam::m_AmplitudeImageFileNames
private

Definition at line 136 of file VirtualRangeCam.h.

std::string ipa_CameraSensors::VirtualRangeCam::m_CameraDataDirectory
private

Directory where the image data resides.

Definition at line 133 of file VirtualRangeCam.h.

int ipa_CameraSensors::VirtualRangeCam::m_CameraIndex
private

Index of the specified camera. Important, when several cameras of the same type are present.

Definition at line 134 of file VirtualRangeCam.h.

cv::Mat ipa_CameraSensors::VirtualRangeCam::m_CoeffsA0
private

a0 z-calibration parameters. One matrix entry corresponds to one pixel

Given a 32 bit swissranger depth value, the real depth value in meteres is given by: z(u,v)=a0(u,v)+a1(u,v)*d(u,v)+a2(u,v)*d(u,v)^2 +a3(u,v)*d(u,v)^3+a4(u,v)*d(u,v)^4+a5(u,v)*d(u,v)^5 +a6(u,v)*d(u,v)^6;

Definition at line 125 of file VirtualRangeCam.h.

cv::Mat ipa_CameraSensors::VirtualRangeCam::m_CoeffsA1
private

a1 z-calibration parameters. One matrix entry corresponds to one pixel

Definition at line 126 of file VirtualRangeCam.h.

cv::Mat ipa_CameraSensors::VirtualRangeCam::m_CoeffsA2
private

a2 z-calibration parameters. One matrix entry corresponds to one pixel

Definition at line 127 of file VirtualRangeCam.h.

cv::Mat ipa_CameraSensors::VirtualRangeCam::m_CoeffsA3
private

a3 z-calibration parameters. One matrix entry corresponds to one pixel

Definition at line 128 of file VirtualRangeCam.h.

cv::Mat ipa_CameraSensors::VirtualRangeCam::m_CoeffsA4
private

a4 z-calibration parameters. One matrix entry corresponds to one pixel

Definition at line 129 of file VirtualRangeCam.h.

cv::Mat ipa_CameraSensors::VirtualRangeCam::m_CoeffsA5
private

a5 z-calibration parameters. One matrix entry corresponds to one pixel

Definition at line 130 of file VirtualRangeCam.h.

cv::Mat ipa_CameraSensors::VirtualRangeCam::m_CoeffsA6
private

a6 z-calibration parameters. One matrix entry corresponds to one pixel

Definition at line 131 of file VirtualRangeCam.h.

bool ipa_CameraSensors::VirtualRangeCam::m_CoeffsInitialized
private

Definition at line 119 of file VirtualRangeCam.h.

std::vector<std::string> ipa_CameraSensors::VirtualRangeCam::m_CoordinateImageFileNames
private

Definition at line 139 of file VirtualRangeCam.h.

int ipa_CameraSensors::VirtualRangeCam::m_ImageHeight
private

Image height.

Definition at line 142 of file VirtualRangeCam.h.

int ipa_CameraSensors::VirtualRangeCam::m_ImageWidth
private

Image width.

Definition at line 141 of file VirtualRangeCam.h.

std::vector<std::string> ipa_CameraSensors::VirtualRangeCam::m_IntensityImageFileNames
private

Definition at line 137 of file VirtualRangeCam.h.

double ipa_CameraSensors::VirtualRangeCam::m_k1
private

Definition at line 144 of file VirtualRangeCam.h.

double ipa_CameraSensors::VirtualRangeCam::m_k2
private

Definition at line 144 of file VirtualRangeCam.h.

double ipa_CameraSensors::VirtualRangeCam::m_p1
private

Definition at line 144 of file VirtualRangeCam.h.

double ipa_CameraSensors::VirtualRangeCam::m_p2
private

Distortion parameters.

Definition at line 144 of file VirtualRangeCam.h.

std::vector<std::string> ipa_CameraSensors::VirtualRangeCam::m_RangeImageFileNames
private

Definition at line 138 of file VirtualRangeCam.h.


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


cob_camera_sensors
Author(s): Jan Fischer , Richard Bormann
autogenerated on Thu Mar 19 2020 03:23:05