Mech-Eye API 2.5.1
API reference documentation for Mech-Eye Industrial 3D Camera
Loading...
Searching...
No Matches
Camera.h
Go to the documentation of this file.
1/*******************************************************************************
2 * BSD 3-Clause License
3 *
4 * Copyright (c) 2016-2025, Mech-Mind Robotics Technologies Co., Ltd.
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 <vector>
39#include "api_global.h"
40#include "CameraProperties.h"
41#include "ErrorStatus.h"
42#include "Frame2DAnd3D.h"
43#include "UserSetManager.h"
44
45namespace mmind {
46
47namespace eye {
48
55{
56public:
61
66
70 Camera(const Camera& other) noexcept;
71
75 Camera& operator=(const Camera& other) noexcept;
76
85 static std::vector<CameraInfo> discoverCameras(unsigned int timeoutMs = 5000);
86
103 ErrorStatus connect(const CameraInfo& info, unsigned int timeoutMs = 5000);
104
121 ErrorStatus connect(const std::string& ipAddress, unsigned int timeoutMs = 5000);
122
127
139 ErrorStatus setHeartbeatInterval(unsigned int timeIntervalMs);
140
151
161
175
187
196
205
224 ErrorStatus capture3D(Frame3D& frame3D, unsigned int timeoutMs = 5000) const;
225
243 ErrorStatus capture3DWithNormal(Frame3D& frame3D, unsigned int timeoutMs = 10000) const;
244
261 ErrorStatus capture2D(Frame2D& frame2D, unsigned int timeoutMs = 5000) const;
262
282 ErrorStatus capture2DAnd3D(Frame2DAnd3D& frame2DAnd3D, unsigned int timeoutMs = 10000) const;
283
305 unsigned int timeoutMs = 15000) const;
306
333 ErrorStatus captureStereo2D(Frame2D& left, Frame2D& right, bool isRectified = false,
334 unsigned int timeoutMs = 5000) const;
335
349
363
383 ErrorStatus saveVirtualDeviceFile(const std::string& fileName);
384
385private:
386 friend class HandEyeCalibration;
387 friend class CameraEvent;
388 friend class InternalInterfaces;
389 std::shared_ptr<class CameraImpl> _cameraImpl;
390};
391
392} // namespace eye
393
394} // namespace mmind
#define MMIND_API_EXPORT
Definition api_global.h:48
The camera event related. Use CameraEvent::getSupportedEvents to get supported events....
Definition CameraEvent.h:61
Operates the camera. Use Camera::connect to connect an available camera, and then call the correspond...
Definition Camera.h:55
static std::vector< CameraInfo > discoverCameras(unsigned int timeoutMs=5000)
Discovers all available cameras and returns the list of information of all available cameras....
ErrorStatus getCameraResolutions(CameraResolutions &resolutions) const
Gets the image resolutions of the camera. Two image resolutions are provided, 2D image (texture) and ...
UserSet & currentUserSet()
Gets the UserSet currently in use.Through UserSet, you can access all available parameters of the cam...
ErrorStatus capture3D(Frame3D &frame3D, unsigned int timeoutMs=5000) const
Projects structured light and captures a single 3D frame. 3D information is computed on the camera....
ErrorStatus captureStereo2D(Frame2D &left, Frame2D &right, bool isRectified=false, unsigned int timeoutMs=5000) const
Captures the 2D images from both 2D cameras in the 3D camera. This method is only available for DEEP,...
ErrorStatus capture2DAnd3D(Frame2DAnd3D &frame2DAnd3D, unsigned int timeoutMs=10000) const
Simultaneously captures a single 2D frame and 3D frame. 3D information is computed on the camera....
ErrorStatus getCameraInfo(CameraInfo &info) const
Gets the basic information of the camera, such as the model, serial number, firmware version,...
ErrorStatus capture2DAnd3DWithNormal(Frame2DAnd3D &frame2DAnd3D, unsigned int timeoutMs=15000) const
Simultaneously captures a single 2D frame and 3D frame. 3D information and normal vector are computed...
ErrorStatus connect(const CameraInfo &info, unsigned int timeoutMs=5000)
Connects to a camera using CameraInfo.
ErrorStatus setPointCloudUnit(CoordinateUnit unit)
Sets the unit of the point cloud.
ErrorStatus getCameraIntrinsics(CameraIntrinsics &intrinsics) const
Gets the camera intrinsic parameters. The camera intrinsic parameters include the intrinsic parameter...
ErrorStatus getCameraStatus(CameraStatus &status) const
Gets various statuses of the camera.
void disconnect()
Disconnects from the camera and releases the associated resources.
ErrorStatus getPointCloudUnit(CoordinateUnit &unit) const
Gets the current unit of the point cloud.
ErrorStatus capture2D(Frame2D &frame2D, unsigned int timeoutMs=5000) const
Captures a single 2D frame using the 2D camera in the 3D camera. The result is retrieved after the ca...
Camera()
Constructor.
ErrorStatus saveVirtualDeviceFile(const std::string &fileName)
Saves the acquired data, Parameter s, and CameraInfo in an MRAW format file that can be loaded as a v...
Camera(const Camera &other) noexcept
Copy constructor.
~Camera()
Destructor.
ErrorStatus setHeartbeatInterval(unsigned int timeIntervalMs)
Sets the time interval at which the client sends periodic heartbeat messages to the camera side....
UserSetManager & userSetManager()
Gets the UserSetManager of the camera. UserSetManager provides various operations for managing all us...
ErrorStatus connect(const std::string &ipAddress, unsigned int timeoutMs=5000)
Connects to a camera using the IP address.
Camera & operator=(const Camera &other) noexcept
Copy assignment.
ErrorStatus capture3DWithNormal(Frame3D &frame3D, unsigned int timeoutMs=10000) const
Projects structured light and captures a single 3D frame. 3D information and normal vector are comput...
Represents the 2D and 3D capture results, which can be obtained by calling Camera::capture2DAnd3D....
Definition Frame2DAnd3D.h:101
Represents the 2D capture result, which can be obtained by calling Camera::capture2D....
Definition Frame2D.h:73
Represents the 3D capture result, which can be obtained by calling Camera::capture3D....
Definition Frame3D.h:91
Definition HandEyeCalibration.h:11
Definition UserSet.h:13
Manages device user sets.
Definition UserSetManager.h:15
CoordinateUnit
The unit of the coordinate data of the point cloud.
Definition CommonTypes.h:16
Definition Camera.h:45
Defines the camera information.
Definition CameraProperties.h:49
Defines the 3D camera intrinsic parameters, including the intrinsic parameters of the texture 2D came...
Definition CameraProperties.h:139
Defines the camera image resolutions, including the resolutions of the 2D image (texture) and depth m...
Definition CameraProperties.h:128
Describes the camera's statuses.
Definition CameraProperties.h:75
Describes the types of errors.
Definition ErrorStatus.h:12