Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
visionary Namespace Reference

Namespaces

 CoLaCommandType
 
 CoLaError
 

Classes

class  AuthenticationLegacy
 
class  AuthenticationSecure
 
struct  CameraParameters
 
struct  ChallengeRequest
 
class  CoLa2ProtocolHandler
 
class  CoLaBProtocolHandler
 
class  CoLaCommand
 
class  CoLaParameterReader
 Class for reading data from a CoLaCommand. More...
 
class  CoLaParameterWriter
 Builder for constructing CoLaCommands. More...
 
class  ControlSession
 
struct  DataSetsActive
 
struct  DEPTHMAP_ELEMENT
 
struct  DEPTHMAP_FLAGS
 
struct  DEVICE_STATUS_ELEMENT
 
struct  DEVICESTATUS_DATA_ACTIVE_MONITORING_CASE
 
struct  DEVICESTATUS_DATA_GENERALSTATUS
 
struct  FIELDINFORMATION_DATA
 
struct  FIELDINFORMATION_ELEMENT
 
class  IAuthentication
 
struct  IMU_ELEMENT
 
struct  IMU_QUATERNION
 
struct  IMU_VECTOR
 
class  IProtocolHandler
 
class  ITransport
 
struct  LOCALIOS_ELEMENT
 
struct  LOCALIOS_OSSDS_STATE
 
struct  LOCALIOS_UNIVERSALIO_CONFIGURED
 
struct  LOCALIOS_UNIVERSALIO_DIRECTION
 
struct  LOCALIOS_UNIVERSALIO_INPUTVALUES
 
struct  LOCALIOS_UNIVERSALIO_OUTPUTVALUES
 
struct  LOGICSIGNALS_DATA
 
struct  LOGICSIGNALS_ELEMENT
 
struct  LOGICSIGNALS_INSTANCESTATE
 
class  PointCloudPlyWriter
 Class for writing point clouds to PLY files. More...
 
struct  PointXYZ
 
struct  PointXYZC
 
struct  ROI_DATA
 
struct  ROI_DATA_RESULT
 
union  ROI_DATA_SAFETY_DATA
 Union for BitSet structure and alternative generic access : ROI distance measurement - safety related information (JAMA 3DTOF-BU_22_SYS-995) More...
 
struct  ROI_ELEMENT
 
class  SafeVisionaryControl
 
class  SafeVisionaryData
 
class  SafeVisionaryDataStream
 
class  TcpSocket
 
struct  UdpProtocolData
 Meta data contained in a UDP header. More...
 
class  UdpSocket
 
class  VisionaryAutoIPScan
 
class  VisionaryControl
 
class  VisionaryData
 
class  VisionaryDataStream
 

Typedefs

typedef std::array< std::uint8_t, 32 > ChallengeResponse
 
typedef std::array< std::uint8_t, 32 > PasswordHash
 

Enumerations

enum  DataHandlerError {
  DataHandlerError::OK, DataHandlerError::PARSE_XML_ERROR, DataHandlerError::INVALID_CRC_SEGMENT_DEPTHMAP, DataHandlerError::INVALID_LENGTH_SEGMENT_DEPTHMAP,
  DataHandlerError::INVALID_VERSION_SEGMENT_DEPTHMAP, DataHandlerError::INVALID_CRC_SEGMENT_DEVICESTATUS, DataHandlerError::INVALID_LENGTH_SEGMENT_DEVICESTATUS, DataHandlerError::INVALID_VERSION_SEGMENT_DEVICESTATUS,
  DataHandlerError::INVALID_CRC_SEGMENT_ROI, DataHandlerError::INVALID_LENGTH_SEGMENT_ROI, DataHandlerError::INVALID_VERSION_SEGMENT_ROI, DataHandlerError::INVALID_CRC_SEGMENT_LOCALIOS,
  DataHandlerError::INVALID_LENGTH_SEGMENT_LOCALIOS, DataHandlerError::INVALID_VERSION_SEGMENT_LOCALIOS, DataHandlerError::INVALID_CRC_SEGMENT_FIELDINFORMATION, DataHandlerError::INVALID_LENGTH_SEGMENT_FIELDINFORMATION,
  DataHandlerError::INVALID_VERSION_SEGMENT_FIELDINFORMATION, DataHandlerError::INVALID_CRC_SEGMENT_LOGICSIGNALS, DataHandlerError::INVALID_LENGTH_SEGMENT_LOGICSIGNALS, DataHandlerError::INVALID_VERSION_SEGMENT_LOGICSIGNALS,
  DataHandlerError::INVALID_CRC_SEGMENT_IMU, DataHandlerError::INVALID_LENGTH_SEGMENT_IMU, DataHandlerError::INVALID_VERSION_SEGMENT_IMU
}
 
enum  DataStreamError {
  DataStreamError::OK, DataStreamError::DATA_RECEIVE_TIMEOUT, DataStreamError::CONNECTION_CLOSED, DataStreamError::PARSE_XML_ERROR,
  DataStreamError::INVALID_VERSION_UDP_HEADER, DataStreamError::INVALID_PACKET_TYPE_UDP_HEADER, DataStreamError::INVALID_LENGTH_UDP_HEADER, DataStreamError::INVALID_CRC_UDP_HEADER,
  DataStreamError::INVALID_BLOB_HEADER, DataStreamError::INVALID_VERSION_BLOB_HEADER, DataStreamError::INVALID_PACKET_TYPE_BLOB_HEADER, DataStreamError::INVALID_BLOB_ID,
  DataStreamError::INVALID_BLOB_NUMBER, DataStreamError::INVALID_UDP_FRAGMENT_NUMBER, DataStreamError::DATA_SEGMENT_DEPTHMAP_ERROR, DataStreamError::DATA_SEGMENT_DEVICESTATUS_ERROR,
  DataStreamError::DATA_SEGMENT_ROI_ERROR, DataStreamError::DATA_SEGMENT_LOCALIOS_ERROR, DataStreamError::DATA_SEGMENT_FIELDINFORMATION_ERROR, DataStreamError::DATA_SEGMENT_LOGICSIGNALS_ERROR,
  DataStreamError::DATA_SEGMENT_IMU_ERROR
}
 
enum  DEVICE_STATUS : std::uint8_t {
  DEVICE_STATUS::DEVICE_STATUS_CONFIGURATION = 0U, DEVICE_STATUS::DEVICE_STATUS_WAIT_FOR_INPUTS = 1U, DEVICE_STATUS::DEVICE_STATUS_APPLICATION_STOPPED = 2U, DEVICE_STATUS::DEVICE_STATUS_NORMAL_OPERATION,
  DEVICE_STATUS::DEVICE_STATUS_INVALID = 255U
}
 
enum  ROI_QUALITY_CLASS { ROI_QUALITY_CLASS_INVALID = 0, ROI_QUALITY_CLASS_HIGH = 1, ROI_QUALITY_CLASS_MODERATE = 2, ROI_QUALITY_CLASS_LOW = 3 }
 

Functions

template<typename T >
bigEndianToNative (T x)
 
char byteswap (char val)
 
double byteswap (double val)
 
float byteswap (float val)
 
int16_t byteswap (int16_t val)
 
int32_t byteswap (int32_t val)
 
int64_t byteswap (int64_t val)
 
int8_t byteswap (int8_t val)
 
uint16_t byteswap (uint16_t val)
 
uint32_t byteswap (uint32_t val)
 
uint64_t byteswap (uint64_t val)
 
uint8_t byteswap (uint8_t val)
 
wchar_t byteswap (wchar_t val)
 
template<typename TAlias , typename T >
byteswapAlias (T val)
 
uint32_t CRC_calcCrc32Block (const void *const pvData, uint32_t u32Length, uint32_t u32InitVal)
 Compute the CRC-32 value of a data block based on a start value. More...
 
uint32_t CRC_calcCrc32CBlock (const void *const pvData, uint32_t u32Length, uint32_t u32InitVal)
 Compute the CRC-32C value of a data block based on a start value. More...
 
template<typename T >
littleEndianToNative (T x)
 
template<typename T >
nativeToBigEndian (T x)
 
template<typename T >
nativeToColaByteOrder (T x)
 
template<typename T >
nativeToLittleEndian (T x)
 
template<typename T >
readUnalignBigEndian (const void *ptr)
 
template<typename T >
readUnalignColaByteOrder (const void *ptr)
 
template<class T >
readUnaligned (const void *ptr)
 
template<typename T >
readUnalignLittleEndian (const void *ptr)
 

Variables

const float bad_point = std::numeric_limits<float>::quiet_NaN()
 
static const uint32_t CRC_au32CRC32CTable [256]
 
static const uint32_t CRC_au32CRCTable [256]
 
static const std::string DEFAULT_BROADCAST_ADDR = "255.255.255.255"
 
static const uint16_t DEFAULT_PORT = 30718
 
constexpr std::uint32_t MAX_FIELDINFORMATION_VALUES = 16u
 
constexpr std::uint32_t MAX_LOGICSIGNALS_VALUES = 20u
 
constexpr std::uint32_t MAX_ROI_VALUES = 5u
 

Detailed Description

Copyright (C) 2023, SICK AG, Waldkirch, Germany Copyright (C) 2023, FZI Forschungszentrum Informatik, Karlsruhe, Germany

Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

Typedef Documentation

◆ ChallengeResponse

typedef std::array<std::uint8_t, 32> visionary::ChallengeResponse

Definition at line 35 of file AuthenticationSecure.h.

◆ PasswordHash

typedef std::array<std::uint8_t, 32> visionary::PasswordHash

Definition at line 34 of file AuthenticationSecure.h.

Enumeration Type Documentation

◆ DataHandlerError

Enumerator
OK 
PARSE_XML_ERROR 
INVALID_CRC_SEGMENT_DEPTHMAP 
INVALID_LENGTH_SEGMENT_DEPTHMAP 
INVALID_VERSION_SEGMENT_DEPTHMAP 
INVALID_CRC_SEGMENT_DEVICESTATUS 
INVALID_LENGTH_SEGMENT_DEVICESTATUS 
INVALID_VERSION_SEGMENT_DEVICESTATUS 
INVALID_CRC_SEGMENT_ROI 
INVALID_LENGTH_SEGMENT_ROI 
INVALID_VERSION_SEGMENT_ROI 
INVALID_CRC_SEGMENT_LOCALIOS 
INVALID_LENGTH_SEGMENT_LOCALIOS 
INVALID_VERSION_SEGMENT_LOCALIOS 
INVALID_CRC_SEGMENT_FIELDINFORMATION 
INVALID_LENGTH_SEGMENT_FIELDINFORMATION 
INVALID_VERSION_SEGMENT_FIELDINFORMATION 
INVALID_CRC_SEGMENT_LOGICSIGNALS 
INVALID_LENGTH_SEGMENT_LOGICSIGNALS 
INVALID_VERSION_SEGMENT_LOGICSIGNALS 
INVALID_CRC_SEGMENT_IMU 
INVALID_LENGTH_SEGMENT_IMU 
INVALID_VERSION_SEGMENT_IMU 

Definition at line 171 of file SafeVisionaryData.h.

◆ DataStreamError

Enumerator
OK 
DATA_RECEIVE_TIMEOUT 
CONNECTION_CLOSED 
PARSE_XML_ERROR 
INVALID_VERSION_UDP_HEADER 
INVALID_PACKET_TYPE_UDP_HEADER 
INVALID_LENGTH_UDP_HEADER 
INVALID_CRC_UDP_HEADER 
INVALID_BLOB_HEADER 
INVALID_VERSION_BLOB_HEADER 
INVALID_PACKET_TYPE_BLOB_HEADER 
INVALID_BLOB_ID 
INVALID_BLOB_NUMBER 
INVALID_UDP_FRAGMENT_NUMBER 
DATA_SEGMENT_DEPTHMAP_ERROR 
DATA_SEGMENT_DEVICESTATUS_ERROR 
DATA_SEGMENT_ROI_ERROR 
DATA_SEGMENT_LOCALIOS_ERROR 
DATA_SEGMENT_FIELDINFORMATION_ERROR 
DATA_SEGMENT_LOGICSIGNALS_ERROR 
DATA_SEGMENT_IMU_ERROR 

Definition at line 40 of file SafeVisionaryDataStream.h.

◆ DEVICE_STATUS

enum visionary::DEVICE_STATUS : std::uint8_t
strong

Enumeration which describes the various states of the device

Enumerator
DEVICE_STATUS_CONFIGURATION 

Device is in state CONFIGURATION

DEVICE_STATUS_WAIT_FOR_INPUTS 

Device is in state WAIT_FOR_INPUTS

DEVICE_STATUS_APPLICATION_STOPPED 

Device is in state APPLICATION_STOPPED

DEVICE_STATUS_NORMAL_OPERATION 

Device is in state NORMAL_OPERATION, application is running

DEVICE_STATUS_INVALID 

Device status is invalid / not initialized

Definition at line 39 of file SafeVisionaryData.h.

◆ ROI_QUALITY_CLASS

Quality classes for measurement accuracy (JAMA 3DTOF-BU_22_SYS-1316)

Enumerator
ROI_QUALITY_CLASS_INVALID 
ROI_QUALITY_CLASS_HIGH 
ROI_QUALITY_CLASS_MODERATE 
ROI_QUALITY_CLASS_LOW 

Definition at line 130 of file SafeVisionaryData.h.

Function Documentation

◆ bigEndianToNative()

template<typename T >
T visionary::bigEndianToNative ( x)
inline

Definition at line 170 of file VisionaryEndian.h.

◆ byteswap() [1/12]

char visionary::byteswap ( char  val)
inline

Definition at line 71 of file VisionaryEndian.h.

◆ byteswap() [2/12]

double visionary::byteswap ( double  val)
inline

Definition at line 127 of file VisionaryEndian.h.

◆ byteswap() [3/12]

float visionary::byteswap ( float  val)
inline

Definition at line 102 of file VisionaryEndian.h.

◆ byteswap() [4/12]

int16_t visionary::byteswap ( int16_t  val)
inline

Definition at line 82 of file VisionaryEndian.h.

◆ byteswap() [5/12]

int32_t visionary::byteswap ( int32_t  val)
inline

Definition at line 98 of file VisionaryEndian.h.

◆ byteswap() [6/12]

int64_t visionary::byteswap ( int64_t  val)
inline

Definition at line 123 of file VisionaryEndian.h.

◆ byteswap() [7/12]

int8_t visionary::byteswap ( int8_t  val)
inline

Definition at line 67 of file VisionaryEndian.h.

◆ byteswap() [8/12]

uint16_t visionary::byteswap ( uint16_t  val)
inline

Definition at line 78 of file VisionaryEndian.h.

◆ byteswap() [9/12]

uint32_t visionary::byteswap ( uint32_t  val)
inline

Definition at line 93 of file VisionaryEndian.h.

◆ byteswap() [10/12]

uint64_t visionary::byteswap ( uint64_t  val)
inline

Definition at line 117 of file VisionaryEndian.h.

◆ byteswap() [11/12]

uint8_t visionary::byteswap ( uint8_t  val)
inline

Definition at line 63 of file VisionaryEndian.h.

◆ byteswap() [12/12]

wchar_t visionary::byteswap ( wchar_t  val)
inline

Definition at line 86 of file VisionaryEndian.h.

◆ byteswapAlias()

template<typename TAlias , typename T >
T visionary::byteswapAlias ( val)
inline

Definition at line 143 of file VisionaryEndian.h.

◆ CRC_calcCrc32Block()

uint32_t visionary::CRC_calcCrc32Block ( const void *const  pvData,
uint32_t  u32Length,
uint32_t  u32InitVal 
)

Compute the CRC-32 value of a data block based on a start value.

Compute the CRC-32 value of a data block based on a start value.

The computation uses the bit reversed CCITT-CRC32 polynomial, see CRC_au32CRCTable.

LSBit first (i.e. bit reversed) algorithm, if valid CRC is at the end of data stream and included in the calculation, the function will return 0 if CRC32 is stored with low byte first (not byte swapped on little endian machines).

Parameters
pvDataPointer to start of data bytes for which CRC is computed (must not be NULL)
u32LengthLength (in bytes) of the data
u32InitValInitial CRC value (either start value or CRC value of previous block in case of incremental CRC calculation)
Returns
the CRC-32 value of the block

Definition at line 86 of file CRC.cpp.

◆ CRC_calcCrc32CBlock()

uint32_t visionary::CRC_calcCrc32CBlock ( const void *const  pvData,
uint32_t  u32Length,
uint32_t  u32InitVal 
)

Compute the CRC-32C value of a data block based on a start value.

Compute the CRC-32 value of a data block based on a start value.

The computation uses the bit reversed CCITT-CRC32C polynomial, see CRC_au32CRC32CTable.

LSBit first (i.e. bit reversed) algorithm, if valid CRC is at the end of data stream and included in the calculation, the function will return 0 if CRC32 is stored with low byte first (not byte swapped on little endian machines).

Parameters
pvDataPointer to start of data bytes for which CRC is computed (must not be NULL)
u32LengthLength (in bytes) of the data
u32InitValInitial CRC value (either start value or CRC value of previous block in case of incremental CRC calculation)
Returns
the CRC-32 value of the block

Definition at line 153 of file CRC.cpp.

◆ littleEndianToNative()

template<typename T >
T visionary::littleEndianToNative ( x)
inline

Definition at line 158 of file VisionaryEndian.h.

◆ nativeToBigEndian()

template<typename T >
T visionary::nativeToBigEndian ( x)
inline

Definition at line 164 of file VisionaryEndian.h.

◆ nativeToColaByteOrder()

template<typename T >
T visionary::nativeToColaByteOrder ( x)
inline

Definition at line 218 of file VisionaryEndian.h.

◆ nativeToLittleEndian()

template<typename T >
T visionary::nativeToLittleEndian ( x)
inline

Definition at line 152 of file VisionaryEndian.h.

◆ readUnalignBigEndian()

template<typename T >
T visionary::readUnalignBigEndian ( const void *  ptr)
inline

Definition at line 205 of file VisionaryEndian.h.

◆ readUnalignColaByteOrder()

template<typename T >
T visionary::readUnalignColaByteOrder ( const void *  ptr)
inline

Definition at line 223 of file VisionaryEndian.h.

◆ readUnaligned()

template<class T >
T visionary::readUnaligned ( const void *  ptr)

Definition at line 48 of file VisionaryEndian.h.

◆ readUnalignLittleEndian()

template<typename T >
T visionary::readUnalignLittleEndian ( const void *  ptr)
inline

Definition at line 211 of file VisionaryEndian.h.

Variable Documentation

◆ bad_point

const float visionary::bad_point = std::numeric_limits<float>::quiet_NaN()

Definition at line 34 of file VisionaryData.cpp.

◆ CRC_au32CRC32CTable

const uint32_t visionary::CRC_au32CRC32CTable[256]
static

Precomputed CRC-32 lookup table bit reversed CCITT-CRC32C polynomial 0x1EDC6F41 (reversed: 0xEDB88320)

Definition at line 102 of file CRC.cpp.

◆ CRC_au32CRCTable

const uint32_t visionary::CRC_au32CRCTable[256]
static

Precomputed CRC-32 lookup table bit reversed CCITT-CRC32 polynomial 0x104C11DB7 (reversed: 0xEDB88320)

Definition at line 28 of file CRC.cpp.

◆ DEFAULT_BROADCAST_ADDR

const std::string visionary::DEFAULT_BROADCAST_ADDR = "255.255.255.255"
static

Definition at line 30 of file VisionaryAutoIPScan.h.

◆ DEFAULT_PORT

const uint16_t visionary::DEFAULT_PORT = 30718
static

Definition at line 29 of file VisionaryAutoIPScan.h.

◆ MAX_FIELDINFORMATION_VALUES

constexpr std::uint32_t visionary::MAX_FIELDINFORMATION_VALUES = 16u
constexpr

Definition at line 286 of file SafeVisionaryData.h.

◆ MAX_LOGICSIGNALS_VALUES

constexpr std::uint32_t visionary::MAX_LOGICSIGNALS_VALUES = 20u
constexpr

Definition at line 316 of file SafeVisionaryData.h.

◆ MAX_ROI_VALUES

constexpr std::uint32_t visionary::MAX_ROI_VALUES = 5u
constexpr

Definition at line 198 of file SafeVisionaryData.h.



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