Mech-Eye API 2.4.0
API reference documentation for Mech-Eye Industrial 3D Camera
Loading...
Searching...
No Matches
Frame3D.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 "Array2D.h"
40#include "ErrorStatus.h"
41#include "CommonTypes.h"
42
43namespace mmind {
44
45namespace eye {
46
50enum struct CoordinateUnit { Millimeter, Meter };
51
55struct PointZ
56{
57 float z{0};
58};
59
64{
65 float x{0};
66 float y{0};
67 float z{0};
68};
69
74{
75 float x{0};
76 float y{0};
77 float z{0};
78 float curvature{0};
79};
80
86{
87 PointXYZ point;
88 NormalVector normal;
89};
90
96
97enum struct FileFormat {
98 PLY,
99 PCD,
100 CSV,
101};
102
111class MMIND_API_EXPORT Frame3D
112{
113public:
118
123
127 Frame3D(const Frame3D& other) noexcept;
128
132 Frame3D& operator=(const Frame3D& other) noexcept;
133
138
143
147 bool isEmpty() const;
148
152 void clear();
153
162
173
184
198 double& yOffset) const;
199
219 bool isOrganized = false) const;
220
240 const std::string& fileName,
241 bool isOrganized = false) const;
242
262 const std::string& fileName, bool isOrganized = false,
263 CoordinateUnit pointCloudUnit = CoordinateUnit::Millimeter);
264
286 const PointCloudWithNormals& pointCloud, FileFormat fileFormat, const std::string& fileName,
287 bool isOrganized = false, CoordinateUnit pointCloudUnit = CoordinateUnit::Millimeter);
288
289private:
290 friend class CameraImpl;
291 friend class Frame2DAnd3D;
292 friend class InternalInterfaces;
293
294 std::shared_ptr<class Frame3DImpl> _impl;
295 Frame3D(std::shared_ptr<Frame3DImpl>& frameImpl);
296};
297
298} // namespace eye
299
300} // namespace mmind
Represents a 2D container of data.
Definition Array2D.h:17
Represents the 2D and 3D capture results, which can be obtained by calling Camera::capture2DAnd3D....
Represents the 3D capture result, which can be obtained by calling Camera::capture3D....
Definition Frame3D.h:112
uint64_t frameId() const
The ID of the Frame3D frame.
ErrorStatus saveUntexturedPointCloudWithNormals(FileFormat fileFormat, const std::string &fileName, bool isOrganized=false) const
Saves the untextured point cloud to a file of the input file format and filename. Each point contains...
DepthMap getOrthogonalDepthMap(double &xScale, double &yScale, double &xOffset, double &yOffset) const
Obtains the 3D data with the PointZ data format. The 3D data is projected under the orthographic proj...
~Frame3D()
Destructor.
static ErrorStatus savePointCloudWithNormals(const PointCloudWithNormals &pointCloud, FileFormat fileFormat, const std::string &fileName, bool isOrganized=false, CoordinateUnit pointCloudUnit=CoordinateUnit::Millimeter)
Saves the untextured point cloud to a file of the input file format and filename. Each point contains...
static ErrorStatus savePointCloud(const PointCloud &pointCloud, FileFormat fileFormat, const std::string &fileName, bool isOrganized=false, CoordinateUnit pointCloudUnit=CoordinateUnit::Millimeter)
Saves the untextured point cloud to a file of the input file format and filename. Each point contains...
void clear()
Clears the data in Frame3D and releases the associated resources.
Frame3D()
Constructor.
PointCloudWithNormals getUntexturedPointCloudWithNormals() const
Gets the organized 3D data map with a PointXYZWithNormals pixel data format. Each point in PointCloud...
bool isEmpty() const
Judges whether Frame3D is empty.
Frame3D & operator=(const Frame3D &other) noexcept
Copy assignment.
Size imageSize() const
Gets the image size of Frame3D.
Frame3D(const Frame3D &other) noexcept
Copy constructor.
ErrorStatus saveUntexturedPointCloud(FileFormat fileFormat, const std::string &fileName, bool isOrganized=false) const
Saves the untextured point cloud to a file of the input file format and filename. Each point contains...
DepthMap getDepthMap() const
Gets the organized 3D data with the PointZ data format. Each point in DepthMap contains the depth (z-...
PointCloud getUntexturedPointCloud() const
Gets the organized 3D data map with a PointXYZ pixel data format. Each point in PointCloud contains t...
Describes the types of errors.
Definition ErrorStatus.h:12
The pixel element struct with the normal vector coordinate (x, y, z) information.
Definition Frame3D.h:74
float curvature
Normal curvature.
Definition Frame3D.h:78
float y
Normal vector Y coordinate, invalid data: nan.
Definition Frame3D.h:76
float z
Normal vector Z coordinate, invalid data: nan.
Definition Frame3D.h:77
float x
Normal vector X coordinate, invalid data: nan.
Definition Frame3D.h:75
Represents a point in UntexturedPointCloud with the coordinate (x, y, z) information.
Definition Frame3D.h:64
float z
Z channel, default unit: mm, invalid data: nan.
Definition Frame3D.h:67
float y
Y channel, default unit: mm, invalid data: nan.
Definition Frame3D.h:66
float x
X channel, default unit: mm, invalid data: nan.
Definition Frame3D.h:65
The pixel element struct in UntexturedPointCloudWithNormals with the coordinate (x,...
Definition Frame3D.h:86
Represents a point in DepthMap with the depth (z-coordinate) information.
Definition Frame3D.h:56
float z
Depth channel, default unit: mm, invalid data: nan.
Definition Frame3D.h:57
Describes a two-dimensional size with a width and a height.
Definition CommonTypes.h:29