Public Member Functions | Static Public Attributes | Protected Member Functions | Private Attributes | List of all members
visionary::SafeVisionaryData Class Reference

#include <SafeVisionaryData.h>

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

Public Member Functions

void clearData (uint32_t changedCounter)
 
void generatePointCloud (std::vector< PointXYZ > &pointCloud) override
 
DataSetsActive getDataSetsActive ()
 
DEVICE_STATUS getDeviceStatus () const
 
DEVICE_STATUS_ELEMENT getDeviceStatusData () const
 Gets Device Status element. More...
 
const std::vector< uint16_t > & getDistanceMap () const
 
const FIELDINFORMATION_DATAgetFieldInformationData () const
 
uint16_t getFlags () const
 
const IMU_ELEMENT getIMUData () const
 
const std::vector< uint16_t > & getIntensityMap () const
 
DataHandlerError getLastError ()
 
LOCALIOS_ELEMENT getLocalIOData () const
 
const LOGICSIGNALS_DATAgetLogicSignalsData () const
 
const ROI_DATAgetRoiData () const
 
const std::vector< uint8_t > & getStateMap () const
 
bool isDistanceMapFiltered () const
 
bool isIntrudedPixelStateValid () const
 
 SafeVisionaryData ()
 
virtual ~SafeVisionaryData ()
 
- Public Member Functions inherited from visionary::VisionaryData
const CameraParametersgetCameraParameters () const
 
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 parseDepthMap (std::vector< uint8_t >::iterator itBuf, size_t length)
 
void transformPointCloud (std::vector< PointXYZ > &pointCloud) const
 
 VisionaryData ()
 
 ~VisionaryData ()
 

Static Public Attributes

static const float DISTANCE_MAP_UNIT = 0.25f
 factor to convert Radial distance map from fixed point to floating point More...
 

Protected Member Functions

bool parseBinaryData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
bool parseDeviceStatusData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
bool parseFieldInformationData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
bool parseIMUData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
bool parseLocalIOsData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
bool parseLogicSignalsData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
bool parseRoiData (std::vector< uint8_t >::iterator itBuf, size_t length)
 
bool parseXML (const std::string &xmlString, uint32_t changeCounter)
 
- Protected Member Functions inherited from visionary::VisionaryData
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)
 

Private Attributes

DataSetsActive m_dataSetsActive
 
DEVICE_STATUS m_deviceStatus
 Contains the received device status. More...
 
DEVICE_STATUS_ELEMENT m_deviceStatusData
 
uint32_t m_distanceByteDepth
 Byte depth of depth map. More...
 
std::vector< uint16_t > m_distanceMap
 Vector containing the depth map. More...
 
FIELDINFORMATION_DATA m_fieldInformationData
 
uint16_t m_flags
 Contains the received flags. More...
 
IMU_ELEMENT m_IMUData
 
uint32_t m_intensityByteDepth
 Byte depth of intensity map. More...
 
std::vector< uint16_t > m_intensityMap
 Vector containing the intensity map. More...
 
DataHandlerError m_lastDataHandlerError
 Stores the last error which occurred while parsing the Blob data segments. More...
 
LOCALIOS_ELEMENT m_localIOsData
 
LOGICSIGNALS_DATA m_logicSignalsData
 
ROI_DATA m_roiData
 Contains the ROI data. More...
 
uint32_t m_stateByteDepth
 Byte depth of pixel state map. More...
 
std::vector< uint8_t > m_stateMap
 Vector containing the pixel state map. More...
 

Additional Inherited Members

- Protected Types inherited from visionary::VisionaryData
enum  ImageType { UNKNOWN, PLANAR, RADIAL }
 
- Protected Attributes inherited from visionary::VisionaryData
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]
 

Detailed Description

Definition at line 356 of file SafeVisionaryData.h.

Constructor & Destructor Documentation

◆ SafeVisionaryData()

visionary::SafeVisionaryData::SafeVisionaryData ( )

Definition at line 67 of file SafeVisionaryData.cpp.

◆ ~SafeVisionaryData()

visionary::SafeVisionaryData::~SafeVisionaryData ( )
virtual

Definition at line 78 of file SafeVisionaryData.cpp.

Member Function Documentation

◆ clearData()

void visionary::SafeVisionaryData::clearData ( uint32_t  changedCounter)
virtual

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 from visionary::VisionaryData.

Definition at line 872 of file SafeVisionaryData.cpp.

◆ generatePointCloud()

void visionary::SafeVisionaryData::generatePointCloud ( std::vector< PointXYZ > &  pointCloud)
overridevirtual

Calculate and return the point cloud in the camera perspective. Units are in meters.

Parameters
[out]vectorcontaining the calculated point cloud

Implements visionary::VisionaryData.

Definition at line 792 of file SafeVisionaryData.cpp.

◆ getDataSetsActive()

DataSetsActive visionary::SafeVisionaryData::getDataSetsActive ( )
virtual

Gets the structure with the active segments.

Returns
Returns the structure with the active segments

Reimplemented from visionary::VisionaryData.

Definition at line 867 of file SafeVisionaryData.cpp.

◆ getDeviceStatus()

DEVICE_STATUS visionary::SafeVisionaryData::getDeviceStatus ( ) const

Gets device status

Returns
received device status

Definition at line 812 of file SafeVisionaryData.cpp.

◆ getDeviceStatusData()

DEVICE_STATUS_ELEMENT visionary::SafeVisionaryData::getDeviceStatusData ( ) const

Gets Device Status element.

Definition at line 837 of file SafeVisionaryData.cpp.

◆ getDistanceMap()

const std::vector< uint16_t > & visionary::SafeVisionaryData::getDistanceMap ( ) const

Gets the radial distance map The unit of the distance map is 1/4 mm.

Returns
vector containing the radial distance map

Definition at line 797 of file SafeVisionaryData.cpp.

◆ getFieldInformationData()

const FIELDINFORMATION_DATA & visionary::SafeVisionaryData::getFieldInformationData ( ) const

Gets Field Information

Returns
received field Information

Definition at line 847 of file SafeVisionaryData.cpp.

◆ getFlags()

uint16_t visionary::SafeVisionaryData::getFlags ( ) const

Gets the flags state map

Returns
flags state

Definition at line 827 of file SafeVisionaryData.cpp.

◆ getIMUData()

const IMU_ELEMENT visionary::SafeVisionaryData::getIMUData ( ) const

Gets IMU data

Returns
received IMU data

Definition at line 857 of file SafeVisionaryData.cpp.

◆ getIntensityMap()

const std::vector< uint16_t > & visionary::SafeVisionaryData::getIntensityMap ( ) const

Gets the intensity map

Returns
vector containing the intensity map

Definition at line 802 of file SafeVisionaryData.cpp.

◆ getLastError()

DataHandlerError visionary::SafeVisionaryData::getLastError ( )

Gets the last error which occurred while parsing the Blob data segments.

Returns
Returns the last error, OK in case there occurred no error

Definition at line 862 of file SafeVisionaryData.cpp.

◆ getLocalIOData()

LOCALIOS_ELEMENT visionary::SafeVisionaryData::getLocalIOData ( ) const

Gets Local I/Os

Returns
received Local I/Os

Definition at line 842 of file SafeVisionaryData.cpp.

◆ getLogicSignalsData()

const LOGICSIGNALS_DATA & visionary::SafeVisionaryData::getLogicSignalsData ( ) const

Gets Logic Signals data

Returns
received Logic Signal data

Definition at line 852 of file SafeVisionaryData.cpp.

◆ getRoiData()

const ROI_DATA & visionary::SafeVisionaryData::getRoiData ( ) const

Gets ROI data

Returns
received ROI data

Definition at line 832 of file SafeVisionaryData.cpp.

◆ getStateMap()

const std::vector< uint8_t > & visionary::SafeVisionaryData::getStateMap ( ) const

Gets the pixel state map

Returns
vector containing the pixel state map

Definition at line 807 of file SafeVisionaryData.cpp.

◆ isDistanceMapFiltered()

bool visionary::SafeVisionaryData::isDistanceMapFiltered ( ) const

Gets the information whether the distance map is filtered.

Returns
returns true in case the distance map is filtered, otherwise returns false

Definition at line 817 of file SafeVisionaryData.cpp.

◆ isIntrudedPixelStateValid()

bool visionary::SafeVisionaryData::isIntrudedPixelStateValid ( ) const

Gets the information whether the intruded pixel state in the pixel state map is valid.

Returns
returns true in case the intruded pixel state is valid, otherwise returns false

Definition at line 822 of file SafeVisionaryData.cpp.

◆ parseBinaryData()

bool visionary::SafeVisionaryData::parseBinaryData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
protectedvirtual

Parse the Binary data part to extract the image data. some variables are commented out, because they are not used in this sample.

Returns
Returns true when parsing was successful.

Implements visionary::VisionaryData.

Definition at line 333 of file SafeVisionaryData.cpp.

◆ parseDeviceStatusData()

bool visionary::SafeVisionaryData::parseDeviceStatusData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
protectedvirtual

Parse the DeviceStatus data from the Blob segment "Device Status".

Returns
Returns true when parsing was successful.

Reimplemented from visionary::VisionaryData.

Definition at line 496 of file SafeVisionaryData.cpp.

◆ parseFieldInformationData()

bool visionary::SafeVisionaryData::parseFieldInformationData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
protectedvirtual

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

Returns
Returns true when parsing was successful.

Reimplemented from visionary::VisionaryData.

Definition at line 611 of file SafeVisionaryData.cpp.

◆ parseIMUData()

bool visionary::SafeVisionaryData::parseIMUData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
protectedvirtual

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

Returns
Returns true when parsing was successful.

Reimplemented from visionary::VisionaryData.

Definition at line 732 of file SafeVisionaryData.cpp.

◆ parseLocalIOsData()

bool visionary::SafeVisionaryData::parseLocalIOsData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
protectedvirtual

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

Returns
Returns true when parsing was successful.

Reimplemented from visionary::VisionaryData.

Definition at line 554 of file SafeVisionaryData.cpp.

◆ parseLogicSignalsData()

bool visionary::SafeVisionaryData::parseLogicSignalsData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
protectedvirtual

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

Returns
Returns true when parsing was successful.

Reimplemented from visionary::VisionaryData.

Definition at line 672 of file SafeVisionaryData.cpp.

◆ parseRoiData()

bool visionary::SafeVisionaryData::parseRoiData ( std::vector< uint8_t >::iterator  itBuf,
size_t  length 
)
protectedvirtual

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

Returns
Returns true when parsing was successful.

Reimplemented from visionary::VisionaryData.

Definition at line 438 of file SafeVisionaryData.cpp.

◆ parseXML()

bool visionary::SafeVisionaryData::parseXML ( const std::string &  xmlString,
uint32_t  changeCounter 
)
protectedvirtual

Parse the XML Metadata part to get information about the sensor and the following image data.

Returns
Returns true when parsing was successful.

Implements visionary::VisionaryData.

Definition at line 80 of file SafeVisionaryData.cpp.

Member Data Documentation

◆ DISTANCE_MAP_UNIT

constexpr float visionary::SafeVisionaryData::DISTANCE_MAP_UNIT = 0.25f
staticconstexpr

factor to convert Radial distance map from fixed point to floating point

Definition at line 422 of file SafeVisionaryData.h.

◆ m_dataSetsActive

DataSetsActive visionary::SafeVisionaryData::m_dataSetsActive
private

Definition at line 481 of file SafeVisionaryData.h.

◆ m_deviceStatus

DEVICE_STATUS visionary::SafeVisionaryData::m_deviceStatus
private

Contains the received device status.

Definition at line 502 of file SafeVisionaryData.h.

◆ m_deviceStatusData

DEVICE_STATUS_ELEMENT visionary::SafeVisionaryData::m_deviceStatusData
private

Definition at line 508 of file SafeVisionaryData.h.

◆ m_distanceByteDepth

uint32_t visionary::SafeVisionaryData::m_distanceByteDepth
private

Byte depth of depth map.

Definition at line 484 of file SafeVisionaryData.h.

◆ m_distanceMap

std::vector<uint16_t> visionary::SafeVisionaryData::m_distanceMap
private

Vector containing the depth map.

Definition at line 493 of file SafeVisionaryData.h.

◆ m_fieldInformationData

FIELDINFORMATION_DATA visionary::SafeVisionaryData::m_fieldInformationData
private

Definition at line 514 of file SafeVisionaryData.h.

◆ m_flags

uint16_t visionary::SafeVisionaryData::m_flags
private

Contains the received flags.

Definition at line 523 of file SafeVisionaryData.h.

◆ m_IMUData

IMU_ELEMENT visionary::SafeVisionaryData::m_IMUData
private

Definition at line 520 of file SafeVisionaryData.h.

◆ m_intensityByteDepth

uint32_t visionary::SafeVisionaryData::m_intensityByteDepth
private

Byte depth of intensity map.

Definition at line 487 of file SafeVisionaryData.h.

◆ m_intensityMap

std::vector<uint16_t> visionary::SafeVisionaryData::m_intensityMap
private

Vector containing the intensity map.

Definition at line 496 of file SafeVisionaryData.h.

◆ m_lastDataHandlerError

DataHandlerError visionary::SafeVisionaryData::m_lastDataHandlerError
private

Stores the last error which occurred while parsing the Blob data segments.

Definition at line 526 of file SafeVisionaryData.h.

◆ m_localIOsData

LOCALIOS_ELEMENT visionary::SafeVisionaryData::m_localIOsData
private

Definition at line 511 of file SafeVisionaryData.h.

◆ m_logicSignalsData

LOGICSIGNALS_DATA visionary::SafeVisionaryData::m_logicSignalsData
private

Definition at line 517 of file SafeVisionaryData.h.

◆ m_roiData

ROI_DATA visionary::SafeVisionaryData::m_roiData
private

Contains the ROI data.

Definition at line 505 of file SafeVisionaryData.h.

◆ m_stateByteDepth

uint32_t visionary::SafeVisionaryData::m_stateByteDepth
private

Byte depth of pixel state map.

Definition at line 490 of file SafeVisionaryData.h.

◆ m_stateMap

std::vector<uint8_t> visionary::SafeVisionaryData::m_stateMap
private

Vector containing the pixel state map.

Definition at line 499 of file SafeVisionaryData.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