Mech-Eye API 2.3.0
API reference documentation for Mech-Eye Industrial 3D Camera
All Classes Functions Variables Enumerations Enumerator Pages
Camera.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 <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
54class MMIND_API_EXPORT Camera
55{
56public:
61
66
70 Camera(const Camera& other) noexcept;
71
75 Camera& operator=(const Camera& other) noexcept;
76
83 static std::vector<CameraInfo> discoverCameras();
84
101 ErrorStatus connect(const CameraInfo& info, unsigned int timeoutMs = 5000);
102
118 ErrorStatus connect(const std::string& ipAddress, unsigned int timeoutMs = 5000);
119
124
136 ErrorStatus setHeartbeatInterval(unsigned int timeIntervalMs);
137
148
158
172
184
192
201
220 ErrorStatus capture3D(Frame3D& frame3D, unsigned int timeoutMs = 5000) const;
221
239 ErrorStatus capture3DWithNormal(Frame3D& frame3D, unsigned int timeoutMs = 10000) const;
240
257 ErrorStatus capture2D(Frame2D& frame2D, unsigned int timeoutMs = 5000) const;
258
278 ErrorStatus capture2DAnd3D(Frame2DAnd3D& frame2DAnd3D, unsigned int timeoutMs = 10000) const;
279
300 unsigned int timeoutMs = 15000) const;
301
328 ErrorStatus captureStereo2D(Frame2D& left, Frame2D& right, bool isRectified = false,
329 unsigned int timeoutMs = 5000) const;
330
331private:
332 friend class HandEyeCalibration;
333 friend class CameraEvent;
334 std::shared_ptr<class CameraImpl> _cameraImpl;
335};
336
337} // namespace eye
338
339} // namespace mmind
The camera event related. Use CameraEvent::registerCameraEventCallback to register an event of intere...
Definition CameraEvent.h:49
Operates the Mech-Eye Industrial 3D Cameras. Use Camera::connect to connect an available camera,...
Definition Camera.h:55
ErrorStatus capture3DWithNormal(Frame3D &frame3D, unsigned int timeoutMs=10000) const
Projects structured light and captures a single 3D frame of the scene. 3D information and normal vect...
UserSet & currentUserSet()
Gets the UserSet currently in effect of the camera. UserSet can access all available parameters of th...
ErrorStatus getCameraIntrinsics(CameraIntrinsics &intrinsics) const
Gets the camera intrinsics. The camera intrinsics contain the texture camera intrinsics and the depth...
Camera()
Constructor.
static std::vector< CameraInfo > discoverCameras()
Discovers all available cameras, and returns the camera information list for them....
ErrorStatus capture2DAnd3DWithNormal(Frame2DAnd3D &frame2DAnd3D, unsigned int timeoutMs=15000) const
Captures simultaneously a single 2D frame and 3D frame of the scene. 3D information and normal vector...
ErrorStatus connect(const std::string &ipAddress, unsigned int timeoutMs=5000)
Connects to a camera via IP address.
ErrorStatus capture2DAnd3D(Frame2DAnd3D &frame2DAnd3D, unsigned int timeoutMs=10000) const
Captures simultaneously a single 2D frame and 3D frame of the scene. 3D information is computed at th...
ErrorStatus getCameraInfo(CameraInfo &info) const
Gets the basic information of the camera, such as camera model, camera serial number,...
ErrorStatus capture3D(Frame3D &frame3D, unsigned int timeoutMs=5000) const
Projects structured light and captures a single 3D frame of the scene. 3D information is computed at ...
~Camera()
Destructor.
ErrorStatus getCameraResolutions(CameraResolutions &resolutions) const
Gets the resolutions information of the camera. The resolutions consists of two parts,...
ErrorStatus getCameraStatus(CameraStatus &status) const
Gets the running status of the camera.
ErrorStatus connect(const CameraInfo &info, unsigned int timeoutMs=5000)
Connects to a camera via CameraInfo.
Camera(const Camera &other) noexcept
Copy constructor.
ErrorStatus setHeartbeatInterval(unsigned int timeIntervalMs)
Sets the time interval at which the client sends periodic heartbeat messages to the camera side....
void disconnect()
Disconnects the camera and releases the associated resources.
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,...
UserSetManager & userSetManager()
Gets the UserSetManager of the camera. UserSetManager provides various operations to manage all user ...
ErrorStatus capture2D(Frame2D &frame2D, unsigned int timeoutMs=5000) const
Captures a single 2D frame using 2D camera mounted on camera of the scene. The capture result will be...
Camera & operator=(const Camera &other) noexcept
Copy assignment.
Represents the 2D and 3D scanning result, which can be obtained by calling Camera::capture2DAnd3D or ...
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
Manages device user sets.
Defines the camera information.
Defines the 3D camera intrinsic, including the texture source camera, depth source camera and the tra...
Defines the camera resolutions information, including texture image resolution and depth map resoluti...
Describes the camera running status.
Describes the types of errors.
Definition ErrorStatus.h:12