Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Static Private Attributes | List of all members
visionary::VisionaryData Class Referenceabstract

#include <VisionaryData.h>

Inheritance diagram for visionary::VisionaryData:
Inheritance graph
[legend]

Public Member Functions

virtual void clearData (uint32_t changedCounter)
 
virtual void generatePointCloud (std::vector< PointXYZ > &pointCloud)=0
 
const CameraParametersgetCameraParameters () const
 
virtual DataSetsActive getDataSetsActive ()
 
uint32_t getFrameNum () const
 
int getHeight () const
 
uint64_t getSegmentTimestampMS (uint8_t segNum) const
 
uint64_t getTimestamp () const
 
uint64_t getTimestampMS () const
 
int getWidth () const
 
virtual bool parseBinaryData (std::vector< uint8_t >::iterator inputBuffer, size_t length)=0
 
virtual bool parseDepthMap (std::vector< uint8_t >::iterator itBuf, size_t length)
 
virtual bool parseDeviceStatusData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
virtual bool parseFieldInformationData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
virtual bool parseIMUData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
virtual bool parseLocalIOsData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
virtual bool parseLogicSignalsData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
virtual bool parseRoiData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
virtual bool parseXML (const std::string &xmlString, uint32_t changeCounter)=0
 
void transformPointCloud (std::vector< PointXYZ > &pointCloud) const
 
 VisionaryData ()
 
 ~VisionaryData ()
 

Protected Types

enum  ImageType { UNKNOWN, PLANAR, RADIAL }
 

Protected Member Functions

void generatePointCloud (const std::vector< uint16_t > &map, const ImageType &imgType, std::vector< PointXYZ > &pointCloud)
 
int getItemLength (std::string dataType)
 
void preCalcCamInfo (const ImageType &type)
 

Protected Attributes

uint64_t m_blobTimestamp
 
CameraParameters m_cameraParams
 
uint_fast32_t m_changeCounter
 Change counter to detect changes in XML. More...
 
uint_fast32_t m_frameNum
 
std::vector< PointXYZm_preCalcCamInfo
 
ImageType m_preCalcCamInfoType
 
float m_scaleZ
 Factor to convert unit of distance image to mm. More...
 
uint64_t m_segmentTimestamp [TOTAL_SEGMENT_NUMBER]
 

Static Private Attributes

static const uint64_t BITMASK_DAY
 
static const uint64_t BITMASK_HOUR
 
static const uint64_t BITMASK_MILLISECOND
 
static const uint64_t BITMASK_MINUTE
 
static const uint64_t BITMASK_MONTH
 
static const uint64_t BITMASK_SECOND
 
static const uint64_t BITMASK_YEAR
 

Detailed Description

Definition at line 72 of file VisionaryData.h.

Member Enumeration Documentation

◆ ImageType

Enumerator
UNKNOWN 
PLANAR 
RADIAL 

Definition at line 198 of file VisionaryData.h.

Constructor & Destructor Documentation

◆ VisionaryData()

visionary::VisionaryData::VisionaryData ( )

Definition at line 36 of file VisionaryData.cpp.

◆ ~VisionaryData()

visionary::VisionaryData::~VisionaryData ( )

Definition at line 44 of file VisionaryData.cpp.

Member Function Documentation

◆ clearData()

virtual void visionary::VisionaryData::clearData ( uint32_t  changedCounter)
inlinevirtual

Clears the data from the last Blob in case the corresponding segment is not available any more. In case the data segment "DepthMap" is not available, use the given changed counter as framenumber. The changed counter is incremented each Blob and is identical to the frame number.

Parameters
[in]changedCountercounter which shall be used as frame number

Reimplemented in visionary::SafeVisionaryData.

Definition at line 189 of file VisionaryData.h.

◆ generatePointCloud() [1/2]

void visionary::VisionaryData::generatePointCloud ( const std::vector< uint16_t > &  map,
const ImageType imgType,
std::vector< PointXYZ > &  pointCloud 
)
protected

Definition at line 125 of file VisionaryData.cpp.

◆ generatePointCloud() [2/2]

virtual void visionary::VisionaryData::generatePointCloud ( std::vector< PointXYZ > &  pointCloud)
pure virtual

◆ getCameraParameters()

const CameraParameters & visionary::VisionaryData::getCameraParameters ( ) const

Definition at line 253 of file VisionaryData.cpp.

◆ getDataSetsActive()

virtual DataSetsActive visionary::VisionaryData::getDataSetsActive ( )
inlinevirtual

Gets the structure with the active segments.

Returns
Returns the structure with the active segments

Reimplemented in visionary::SafeVisionaryData.

Definition at line 194 of file VisionaryData.h.

◆ getFrameNum()

uint32_t visionary::VisionaryData::getFrameNum ( ) const

Definition at line 209 of file VisionaryData.cpp.

◆ getHeight()

int visionary::VisionaryData::getHeight ( ) const

Definition at line 199 of file VisionaryData.cpp.

◆ getItemLength()

int visionary::VisionaryData::getItemLength ( std::string  dataType)
protected

Definition at line 46 of file VisionaryData.cpp.

◆ getSegmentTimestampMS()

uint64_t visionary::VisionaryData::getSegmentTimestampMS ( uint8_t  segNum) const

Definition at line 236 of file VisionaryData.cpp.

◆ getTimestamp()

uint64_t visionary::VisionaryData::getTimestamp ( ) const

Definition at line 214 of file VisionaryData.cpp.

◆ getTimestampMS()

uint64_t visionary::VisionaryData::getTimestampMS ( ) const

Definition at line 219 of file VisionaryData.cpp.

◆ getWidth()

int visionary::VisionaryData::getWidth ( ) const

Definition at line 204 of file VisionaryData.cpp.

◆ parseBinaryData()

virtual bool visionary::VisionaryData::parseBinaryData ( std::vector< uint8_t >::iterator  inputBuffer,
size_t  length 
)
pure virtual

◆ parseDepthMap()

virtual bool visionary::VisionaryData::parseDepthMap ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
inlinevirtual

Parse the device status from the Blob segment "DepthMap".

Returns
Returns true when parsing was successful.

Definition at line 122 of file VisionaryData.h.

◆ parseDeviceStatusData()

virtual bool visionary::VisionaryData::parseDeviceStatusData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
inlinevirtual

Parse the Device status data from the Blob segment "Device Status"

Returns
Returns true when parsing was successful.

Reimplemented in visionary::SafeVisionaryData.

Definition at line 140 of file VisionaryData.h.

◆ parseFieldInformationData()

virtual bool visionary::VisionaryData::parseFieldInformationData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
inlinevirtual

Parse the Field Information data from the Blob segment "Field Information"

Returns
Returns true when parsing was successful.

Reimplemented in visionary::SafeVisionaryData.

Definition at line 158 of file VisionaryData.h.

◆ parseIMUData()

virtual bool visionary::VisionaryData::parseIMUData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
inlinevirtual

Parse the IMU data from the Blob segment "IMU"

Returns
Returns true when parsing was successful.

Reimplemented in visionary::SafeVisionaryData.

Definition at line 176 of file VisionaryData.h.

◆ parseLocalIOsData()

virtual bool visionary::VisionaryData::parseLocalIOsData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
inlinevirtual

Parse the Local I/Os data from the Blob segment "Local I/Os"

Returns
Returns true when parsing was successful.

Reimplemented in visionary::SafeVisionaryData.

Definition at line 149 of file VisionaryData.h.

◆ parseLogicSignalsData()

virtual bool visionary::VisionaryData::parseLogicSignalsData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
inlinevirtual

Parse the Logic Signals data from the Blob segment "Logic Signals"

Returns
Returns true when parsing was successful.

Reimplemented in visionary::SafeVisionaryData.

Definition at line 167 of file VisionaryData.h.

◆ parseRoiData()

virtual bool visionary::VisionaryData::parseRoiData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
inlinevirtual

Parse the ROI data from the Blob segment "ROI".

Returns
Returns true when parsing was successful.

Reimplemented in visionary::SafeVisionaryData.

Definition at line 131 of file VisionaryData.h.

◆ parseXML()

virtual bool visionary::VisionaryData::parseXML ( const std::string &  xmlString,
uint32_t  changeCounter 
)
pure virtual

◆ preCalcCamInfo()

void visionary::VisionaryData::preCalcCamInfo ( const ImageType type)
protected

Definition at line 70 of file VisionaryData.cpp.

◆ transformPointCloud()

void visionary::VisionaryData::transformPointCloud ( std::vector< PointXYZ > &  pointCloud) const

Definition at line 172 of file VisionaryData.cpp.

Member Data Documentation

◆ BITMASK_DAY

const uint64_t visionary::VisionaryData::BITMASK_DAY
staticprivate
Initial value:
=
0x7C000000000

Definition at line 260 of file VisionaryData.h.

◆ BITMASK_HOUR

const uint64_t visionary::VisionaryData::BITMASK_HOUR
staticprivate
Initial value:
=
0x7C00000

Definition at line 262 of file VisionaryData.h.

◆ BITMASK_MILLISECOND

const uint64_t visionary::VisionaryData::BITMASK_MILLISECOND
staticprivate
Initial value:
=
0x3FF

Definition at line 268 of file VisionaryData.h.

◆ BITMASK_MINUTE

const uint64_t visionary::VisionaryData::BITMASK_MINUTE
staticprivate
Initial value:
=
0x3F0000

Definition at line 264 of file VisionaryData.h.

◆ BITMASK_MONTH

const uint64_t visionary::VisionaryData::BITMASK_MONTH
staticprivate
Initial value:
=
0x780000000000

Definition at line 258 of file VisionaryData.h.

◆ BITMASK_SECOND

const uint64_t visionary::VisionaryData::BITMASK_SECOND
staticprivate
Initial value:
=
0xFC00

Definition at line 266 of file VisionaryData.h.

◆ BITMASK_YEAR

const uint64_t visionary::VisionaryData::BITMASK_YEAR
staticprivate
Initial value:
=
0x7FF800000000000

Definition at line 256 of file VisionaryData.h.

◆ m_blobTimestamp

uint64_t visionary::VisionaryData::m_blobTimestamp
protected

Definition at line 239 of file VisionaryData.h.

◆ m_cameraParams

CameraParameters visionary::VisionaryData::m_cameraParams
protected

Definition at line 223 of file VisionaryData.h.

◆ m_changeCounter

uint_fast32_t visionary::VisionaryData::m_changeCounter
protected

Change counter to detect changes in XML.

Definition at line 230 of file VisionaryData.h.

◆ m_frameNum

uint_fast32_t visionary::VisionaryData::m_frameNum
protected

Dataset Version 1: incremented on each received image Dataset Version 2: framenumber received with dataset

Definition at line 235 of file VisionaryData.h.

◆ m_preCalcCamInfo

std::vector<PointXYZ> visionary::VisionaryData::m_preCalcCamInfo
protected

Definition at line 249 of file VisionaryData.h.

◆ m_preCalcCamInfoType

ImageType visionary::VisionaryData::m_preCalcCamInfoType
protected

Definition at line 247 of file VisionaryData.h.

◆ m_scaleZ

float visionary::VisionaryData::m_scaleZ
protected

Factor to convert unit of distance image to mm.

Definition at line 227 of file VisionaryData.h.

◆ m_segmentTimestamp

uint64_t visionary::VisionaryData::m_segmentTimestamp[TOTAL_SEGMENT_NUMBER]
protected

Definition at line 243 of file VisionaryData.h.


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


sick_safevisionary_base
Author(s):
autogenerated on Sat Oct 21 2023 02:24:26