#include <SafeVisionaryData.h>
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_DATA & | getFieldInformationData () 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_DATA & | getLogicSignalsData () const |
const ROI_DATA & | getRoiData () const |
const std::vector< uint8_t > & | getStateMap () const |
bool | isDistanceMapFiltered () const |
bool | isIntrudedPixelStateValid () const |
SafeVisionaryData () | |
virtual | ~SafeVisionaryData () |
![]() | |
const CameraParameters & | getCameraParameters () 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) |
![]() | |
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 | |
![]() | |
enum | ImageType { UNKNOWN, PLANAR, RADIAL } |
![]() | |
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< PointXYZ > | m_preCalcCamInfo |
ImageType | m_preCalcCamInfoType |
float | m_scaleZ |
Factor to convert unit of distance image to mm. More... | |
uint64_t | m_segmentTimestamp [TOTAL_SEGMENT_NUMBER] |
Definition at line 356 of file SafeVisionaryData.h.
visionary::SafeVisionaryData::SafeVisionaryData | ( | ) |
Definition at line 67 of file SafeVisionaryData.cpp.
|
virtual |
Definition at line 78 of file SafeVisionaryData.cpp.
|
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.
[in] | changedCounter | counter which shall be used as frame number |
Reimplemented from visionary::VisionaryData.
Definition at line 872 of file SafeVisionaryData.cpp.
|
overridevirtual |
Calculate and return the point cloud in the camera perspective. Units are in meters.
[out] | vector | containing the calculated point cloud |
Implements visionary::VisionaryData.
Definition at line 792 of file SafeVisionaryData.cpp.
|
virtual |
Gets the structure with the active segments.
Reimplemented from visionary::VisionaryData.
Definition at line 867 of file SafeVisionaryData.cpp.
DEVICE_STATUS visionary::SafeVisionaryData::getDeviceStatus | ( | ) | const |
Gets device status
Definition at line 812 of file SafeVisionaryData.cpp.
DEVICE_STATUS_ELEMENT visionary::SafeVisionaryData::getDeviceStatusData | ( | ) | const |
Gets Device Status element.
Definition at line 837 of file SafeVisionaryData.cpp.
const std::vector< uint16_t > & visionary::SafeVisionaryData::getDistanceMap | ( | ) | const |
Gets the radial distance map The unit of the distance map is 1/4 mm.
Definition at line 797 of file SafeVisionaryData.cpp.
const FIELDINFORMATION_DATA & visionary::SafeVisionaryData::getFieldInformationData | ( | ) | const |
Gets Field Information
Definition at line 847 of file SafeVisionaryData.cpp.
uint16_t visionary::SafeVisionaryData::getFlags | ( | ) | const |
const IMU_ELEMENT visionary::SafeVisionaryData::getIMUData | ( | ) | const |
const std::vector< uint16_t > & visionary::SafeVisionaryData::getIntensityMap | ( | ) | const |
Gets the intensity map
Definition at line 802 of file SafeVisionaryData.cpp.
DataHandlerError visionary::SafeVisionaryData::getLastError | ( | ) |
Gets the last error which occurred while parsing the Blob data segments.
Definition at line 862 of file SafeVisionaryData.cpp.
LOCALIOS_ELEMENT visionary::SafeVisionaryData::getLocalIOData | ( | ) | const |
const LOGICSIGNALS_DATA & visionary::SafeVisionaryData::getLogicSignalsData | ( | ) | const |
Gets Logic Signals data
Definition at line 852 of file SafeVisionaryData.cpp.
const ROI_DATA & visionary::SafeVisionaryData::getRoiData | ( | ) | const |
const std::vector< uint8_t > & visionary::SafeVisionaryData::getStateMap | ( | ) | const |
Gets the pixel state map
Definition at line 807 of file SafeVisionaryData.cpp.
bool visionary::SafeVisionaryData::isDistanceMapFiltered | ( | ) | const |
Gets the information whether the distance map is filtered.
Definition at line 817 of file SafeVisionaryData.cpp.
bool visionary::SafeVisionaryData::isIntrudedPixelStateValid | ( | ) | const |
Gets the information whether the intruded pixel state in the pixel state map is valid.
Definition at line 822 of file SafeVisionaryData.cpp.
|
protectedvirtual |
Parse the Binary data part to extract the image data. some variables are commented out, because they are not used in this sample.
Implements visionary::VisionaryData.
Definition at line 333 of file SafeVisionaryData.cpp.
|
protectedvirtual |
Parse the DeviceStatus data from the Blob segment "Device Status".
Reimplemented from visionary::VisionaryData.
Definition at line 496 of file SafeVisionaryData.cpp.
|
protectedvirtual |
Parse the field Information data from the Blob segment "Field Information ".
Reimplemented from visionary::VisionaryData.
Definition at line 611 of file SafeVisionaryData.cpp.
|
protectedvirtual |
Parse the IMU data from the Blob segment "IMU".
Reimplemented from visionary::VisionaryData.
Definition at line 732 of file SafeVisionaryData.cpp.
|
protectedvirtual |
Parse the Local I/Os data from the Blob segment "local I/Os".
Reimplemented from visionary::VisionaryData.
Definition at line 554 of file SafeVisionaryData.cpp.
|
protectedvirtual |
Parse the Logic Signals data from the Blob segment "Logic Signals".
Reimplemented from visionary::VisionaryData.
Definition at line 672 of file SafeVisionaryData.cpp.
|
protectedvirtual |
Parse the ROI data from the Blob segment "ROI".
Reimplemented from visionary::VisionaryData.
Definition at line 438 of file SafeVisionaryData.cpp.
|
protectedvirtual |
Parse the XML Metadata part to get information about the sensor and the following image data.
Implements visionary::VisionaryData.
Definition at line 80 of file SafeVisionaryData.cpp.
|
staticconstexpr |
factor to convert Radial distance map from fixed point to floating point
Definition at line 422 of file SafeVisionaryData.h.
|
private |
Definition at line 481 of file SafeVisionaryData.h.
|
private |
Contains the received device status.
Definition at line 502 of file SafeVisionaryData.h.
|
private |
Definition at line 508 of file SafeVisionaryData.h.
|
private |
Byte depth of depth map.
Definition at line 484 of file SafeVisionaryData.h.
|
private |
Vector containing the depth map.
Definition at line 493 of file SafeVisionaryData.h.
|
private |
Definition at line 514 of file SafeVisionaryData.h.
|
private |
Contains the received flags.
Definition at line 523 of file SafeVisionaryData.h.
|
private |
Definition at line 520 of file SafeVisionaryData.h.
|
private |
Byte depth of intensity map.
Definition at line 487 of file SafeVisionaryData.h.
|
private |
Vector containing the intensity map.
Definition at line 496 of file SafeVisionaryData.h.
|
private |
Stores the last error which occurred while parsing the Blob data segments.
Definition at line 526 of file SafeVisionaryData.h.
|
private |
Definition at line 511 of file SafeVisionaryData.h.
|
private |
Definition at line 517 of file SafeVisionaryData.h.
|
private |
Contains the ROI data.
Definition at line 505 of file SafeVisionaryData.h.
|
private |
Byte depth of pixel state map.
Definition at line 490 of file SafeVisionaryData.h.
|
private |
Vector containing the pixel state map.
Definition at line 499 of file SafeVisionaryData.h.