Mech-Eye API 2.3.1
API reference documentation for Mech-Eye Industrial 3D Camera
All Classes Functions Variables Enumerations Enumerator Pages
Frame2DAnd3D.h
1/*******************************************************************************
2 * BSD 3-Clause License
3 *
4 * Copyright (c) 2016-2024, Mech-Mind Robotics
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions are met:
9 *
10 * 1. Redistributions of source code must retain the above copyright notice, this
11 * list of conditions and the following disclaimer.
12 *
13 * 2. Redistributions in binary form must reproduce the above copyright notice,
14 * this list of conditions and the following disclaimer in the documentation
15 * and/or other materials provided with the distribution.
16 *
17 * 3. Neither the name of the copyright holder nor the names of its
18 * contributors may be used to endorse or promote products derived from
19 * this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
25 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
26 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
29 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
30 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31 *
32 * Info: https://www.mech-mind.com/
33 *
34 ******************************************************************************/
35
36#pragma once
37#include <memory>
38#include "api_global.h"
39#include "Frame2D.h"
40#include "Frame3D.h"
41
42namespace mmind {
43
44namespace eye {
45
51{
52 float x{0};
53 float y{0};
54 float z{0};
55 uint8_t b{0};
56 uint8_t g{0};
57 uint8_t r{0};
58};
59
65{
66 PointXYZBGR colorPoint;
67 NormalVector normal;
68};
69
72
80class MMIND_API_EXPORT Frame2DAnd3D
81{
82public:
87
92
96 Frame2DAnd3D(const Frame2DAnd3D& other) noexcept;
97
101 Frame2DAnd3D& operator=(const Frame2DAnd3D& other) noexcept;
102
107
112
116 void clear();
117
126
137
152 ErrorStatus saveTexturedPointCloud(FileFormat fileFormat, const std::string& fileName,
153 bool isOrganized = false) const;
154
172 const std::string& fileName,
173 bool isOrganized = false) const;
174
189 static ErrorStatus savePointCloud(const TexturedPointCloud& pointCloud, FileFormat fileFormat,
190 const std::string& fileName, bool isOrganized = false);
191
209 FileFormat fileFormat, const std::string& fileName,
210 bool isOrganized = false);
211
212private:
213 std::shared_ptr<class Frame2DAnd3DImpl> _impl;
214 friend class CameraImpl;
215 Frame2DAnd3D(Frame2DAnd3DImpl* frameImpl);
216};
217
218} // namespace eye
219
220} // namespace mmind
Represents a 2D container of data.
Definition Array2D.h:17
Represents the 2D and 3D scanning result, which can be obtained by calling Camera::capture2DAnd3D or ...
TexturedPointCloudWithNormals getTexturedPointCloudWithNormals() const
Gets the pixel-aligned 2D and 3D data with the PointXYZBGRWithNormals pixel data format....
~Frame2DAnd3D()
Destructor.
ErrorStatus saveTexturedPointCloudWithNormals(FileFormat fileFormat, const std::string &fileName, bool isOrganized=false) const
Saves the textured point cloud to a file with input file format and input file name....
static ErrorStatus savePointCloudWithNormals(const TexturedPointCloudWithNormals &pointCloud, FileFormat fileFormat, const std::string &fileName, bool isOrganized=false)
Saves the textured point cloud to a file with input file format and input file name....
Frame2D frame2D() const
Gets the Frame2D data part.
ErrorStatus saveTexturedPointCloud(FileFormat fileFormat, const std::string &fileName, bool isOrganized=false) const
Saves the textured point cloud to a file with input file format and input file name....
Frame2DAnd3D()
Constructor.
Frame2DAnd3D(const Frame2DAnd3D &other) noexcept
Copy constructor.
static ErrorStatus savePointCloud(const TexturedPointCloud &pointCloud, FileFormat fileFormat, const std::string &fileName, bool isOrganized=false)
Saves the textured point cloud to a file with input file format and input file name....
Frame2DAnd3D & operator=(const Frame2DAnd3D &other) noexcept
Copy assignment.
Frame3D frame3D() const
Gets the Frame3D data part.
TexturedPointCloud getTexturedPointCloud() const
Gets the pixel-aligned 2D and 3D data with the PointXYZBGR pixel data format. Each point in TexturedP...
void clear()
Clears the data in Frame2DAnd3D and releases the related resources.
Represents the 2D scanning result, which can be obtained by calling Camera::capture2D....
Definition Frame2D.h:73
Represents the 3D scanning result, which can be obtained by calling Camera::capture3D or Camera::capt...
Definition Frame3D.h:105
Describes the types of errors.
Definition ErrorStatus.h:12
The pixel element struct with normal vector X, Y, and Z information.
Definition Frame3D.h:69
The pixel element struct in TexturedPointCloud with X, Y, Z, blue, green, and red information.
float z
Z channel, unit: mm, invalid data: nan.
float y
Y channel, unit: mm, invalid data: nan.
uint8_t r
Red channel.
uint8_t b
Blue channel.
uint8_t g
Green channel.
float x
X channel, unit: mm, invalid data: nan.
The pixel element struct in TexturedPointCloudWithNormals with X, Y, Z, blue, green,...