sick_visionary_cpp_shared
src
VisionaryTMiniData.h
Go to the documentation of this file.
1
//
2
// Copyright (c) 2023 SICK AG, Waldkirch
3
//
4
// SPDX-License-Identifier: Unlicense
5
6
#pragma once
7
8
#include "
VisionaryData.h
"
9
10
#include <cstddef>
// for size_t
11
#include <cstdint>
12
#include <string>
13
#include <vector>
14
15
namespace
visionary
{
16
17
class
VisionaryTMiniData
:
public
VisionaryData
18
{
19
public
:
20
VisionaryTMiniData
();
21
~VisionaryTMiniData
()
override
;
22
23
//-----------------------------------------------
24
// Getter Functions
25
26
// Gets the radial distance map
27
// The unit of the distancemap is 1/4 mm
28
const
std::vector<std::uint16_t>&
getDistanceMap
()
const
;
29
30
// Gets the intensity map
31
const
std::vector<std::uint16_t>&
getIntensityMap
()
const
;
32
33
// Gets the state map
34
const
std::vector<std::uint16_t>&
getStateMap
()
const
;
35
36
// Calculate and return the Point Cloud in the camera perspective. Units are in meters.
37
void
generatePointCloud
(std::vector<PointXYZ>& pointCloud)
override
;
38
39
// factor to convert Radial distance map from fixed point to floating point
40
static
const
float
DISTANCE_MAP_UNIT
;
41
42
protected
:
43
//-----------------------------------------------
44
// functions for parsing received blob
45
46
// Parse the XML Metadata part to get information about the sensor and the following image data.
47
// This function uses boost library. An other XML parser is needed to remove boost from source.
48
// Returns true when parsing was successful.
49
bool
parseXML
(
const
std::string& xmlString, std::uint32_t changeCounter)
override
;
50
51
// Parse the Binary data part to extract the image data.
52
// some variables are commented out, because they are not used in this sample.
53
// Returns true when parsing was successful.
54
bool
parseBinaryData
(std::vector<uint8_t>::iterator itBuf, std::size_t size)
override
;
55
56
private
:
57
// Indicator for the received data sets
58
DataSetsActive
m_dataSetsActive
;
59
60
// Byte depth of images
61
std::size_t
m_distanceByteDepth
,
m_intensityByteDepth
,
m_stateByteDepth
;
62
63
// Pointers to the image data
64
std::vector<std::uint16_t>
m_distanceMap
;
65
std::vector<std::uint16_t>
m_intensityMap
;
66
std::vector<std::uint16_t>
m_stateMap
;
67
};
68
69
}
// namespace visionary
visionary::VisionaryTMiniData::m_intensityMap
std::vector< std::uint16_t > m_intensityMap
Definition:
VisionaryTMiniData.h:65
visionary::VisionaryTMiniData::VisionaryTMiniData
VisionaryTMiniData()
Definition:
VisionaryTMiniData.cpp:43
visionary::VisionaryTMiniData::getStateMap
const std::vector< std::uint16_t > & getStateMap() const
Definition:
VisionaryTMiniData.cpp:285
visionary::VisionaryTMiniData
Definition:
VisionaryTMiniData.h:17
visionary
Definition:
MD5.cpp:44
visionary::VisionaryTMiniData::m_intensityByteDepth
std::size_t m_intensityByteDepth
Definition:
VisionaryTMiniData.h:61
visionary::DataSetsActive
Definition:
VisionaryData.h:34
visionary::VisionaryTMiniData::m_stateByteDepth
std::size_t m_stateByteDepth
Definition:
VisionaryTMiniData.h:61
visionary::VisionaryTMiniData::~VisionaryTMiniData
~VisionaryTMiniData() override
VisionaryData.h
visionary::VisionaryTMiniData::m_distanceByteDepth
std::size_t m_distanceByteDepth
Definition:
VisionaryTMiniData.h:61
visionary::VisionaryTMiniData::getDistanceMap
const std::vector< std::uint16_t > & getDistanceMap() const
Definition:
VisionaryTMiniData.cpp:275
visionary::VisionaryTMiniData::getIntensityMap
const std::vector< std::uint16_t > & getIntensityMap() const
Definition:
VisionaryTMiniData.cpp:280
visionary::VisionaryTMiniData::parseBinaryData
bool parseBinaryData(std::vector< uint8_t >::iterator itBuf, std::size_t size) override
Definition:
VisionaryTMiniData.cpp:128
visionary::VisionaryTMiniData::m_dataSetsActive
DataSetsActive m_dataSetsActive
Definition:
VisionaryTMiniData.h:58
visionary::VisionaryData
Definition:
VisionaryData.h:49
visionary::VisionaryTMiniData::m_stateMap
std::vector< std::uint16_t > m_stateMap
Definition:
VisionaryTMiniData.h:66
visionary::VisionaryTMiniData::m_distanceMap
std::vector< std::uint16_t > m_distanceMap
Definition:
VisionaryTMiniData.h:64
visionary::VisionaryTMiniData::generatePointCloud
void generatePointCloud(std::vector< PointXYZ > &pointCloud) override
Definition:
VisionaryTMiniData.cpp:270
visionary::VisionaryTMiniData::parseXML
bool parseXML(const std::string &xmlString, std::uint32_t changeCounter) override
Definition:
VisionaryTMiniData.cpp:50
visionary::VisionaryTMiniData::DISTANCE_MAP_UNIT
static const float DISTANCE_MAP_UNIT
Definition:
VisionaryTMiniData.h:40
sick_visionary_ros
Author(s): SICK AG TechSupport 3D Snapshot
autogenerated on Thu Feb 8 2024 03:56:19