Mech-Eye API 2.3.3
API reference documentation for Mech-Eye Industrial 3D Camera
Loading...
Searching...
No Matches
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
119 ErrorStatus connect(const std::string& ipAddress, unsigned int timeoutMs = 5000);
120
125
137 ErrorStatus setHeartbeatInterval(unsigned int timeIntervalMs);
138
149
159
173
185
194
203
222 ErrorStatus capture3D(Frame3D& frame3D, unsigned int timeoutMs = 5000) const;
223
241 ErrorStatus capture3DWithNormal(Frame3D& frame3D, unsigned int timeoutMs = 10000) const;
242
259 ErrorStatus capture2D(Frame2D& frame2D, unsigned int timeoutMs = 5000) const;
260
280 ErrorStatus capture2DAnd3D(Frame2DAnd3D& frame2DAnd3D, unsigned int timeoutMs = 10000) const;
281
303 unsigned int timeoutMs = 15000) const;
304
331 ErrorStatus captureStereo2D(Frame2D& left, Frame2D& right, bool isRectified = false,
332 unsigned int timeoutMs = 5000) const;
333
334private:
335 friend class HandEyeCalibration;
336 friend class CameraEvent;
337 friend class InternalInterfaces;
338 std::shared_ptr<class CameraImpl> _cameraImpl;
339};
340
341} // namespace eye
342
343} // namespace mmind
The camera event related. Use CameraEvent::registerCameraEventCallback to register an event of intere...
Definition CameraEvent.h:49
Operates the camera. Use Camera::connect to connect an available camera, and then call the correspond...
Definition Camera.h:55
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...
UserSet & currentUserSet()
Gets the UserSet currently in use.Through UserSet, you can access all available parameters of the cam...
ErrorStatus getCameraIntrinsics(CameraIntrinsics &intrinsics) const
Gets the camera intrinsic parameters. The camera intrinsic parameters include the intrinsic parameter...
Camera()
Constructor.
static std::vector< CameraInfo > discoverCameras()
Discovers all available cameras and returns the list of information of all available cameras....
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 std::string &ipAddress, unsigned int timeoutMs=5000)
Connects to a camera using the IP address.
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 capture3D(Frame3D &frame3D, unsigned int timeoutMs=5000) const
Projects structured light and captures a single 3D frame. 3D information is computed on the camera....
~Camera()
Destructor.
ErrorStatus getCameraResolutions(CameraResolutions &resolutions) const
Gets the image resolutions of the camera. Two image resolutions are provided, 2D image (texture) and ...
ErrorStatus getCameraStatus(CameraStatus &status) const
Gets various statuses of the camera.
ErrorStatus connect(const CameraInfo &info, unsigned int timeoutMs=5000)
Connects to a camera using 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 from 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 for managing all us...
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 & operator=(const Camera &other) noexcept
Copy assignment.
Represents the 2D and 3D capture results, which can be obtained by calling Camera::capture2DAnd3D....
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:106
Manages device user sets.
Defines the camera information.
Defines the 3D camera intrinsic parameters, including the intrinsic parameters of the texture 2D came...
Defines the camera image resolutions, including the resolutions of the 2D image (texture) and depth m...
Describes the camera's statuses.
Describes the types of errors.
Definition ErrorStatus.h:12