Mech-Eye API 2.3.1
API reference documentation for Mech-Eye Industrial 3D Camera
All Classes Functions Variables Enumerations Enumerator Pages
Public Member Functions | Static Public Member Functions | Friends | List of all members
mmind::eye::Camera Class Reference

Operates the Mech-Eye Industrial 3D Cameras. Use Camera::connect to connect an available camera, and then you can use the camera to capture 2D and 3D frames, configure parameters and so on. More...

#include <Camera.h>

Public Member Functions

 Camera ()
 Constructor.
 
 ~Camera ()
 Destructor.
 
 Camera (const Camera &other) noexcept
 Copy constructor.
 
Cameraoperator= (const Camera &other) noexcept
 Copy assignment.
 
ErrorStatus connect (const CameraInfo &info, unsigned int timeoutMs=5000)
 Connects to a camera via CameraInfo.
 
ErrorStatus connect (const std::string &ipAddress, unsigned int timeoutMs=5000)
 Connects to a camera via IP address.
 
void disconnect ()
 Disconnects the camera and releases the associated resources.
 
ErrorStatus setHeartbeatInterval (unsigned int timeIntervalMs)
 Sets the time interval at which the client sends periodic heartbeat messages to the camera side. The default time interval is 10s.
 
ErrorStatus getCameraInfo (CameraInfo &info) const
 Gets the basic information of the camera, such as camera model, camera serial number, firmware version, and IP setting, etc.
 
ErrorStatus getCameraStatus (CameraStatus &status) const
 Gets the running status of the camera.
 
ErrorStatus getCameraIntrinsics (CameraIntrinsics &intrinsics) const
 Gets the camera intrinsics. The camera intrinsics contain the texture camera intrinsics and the depth camera intrinsics based on the pinhole camera model, which correspond to the 2D and 3D scanning results Frame2D and Frame3D. The camera intrinsics also contain the transformation relationship between depth camera and texture camera.
 
ErrorStatus getCameraResolutions (CameraResolutions &resolutions) const
 Gets the resolutions information of the camera. The resolutions consists of two parts, texture and depth, which correspond to the 2D and 3D scanning results Frame2D and Frame3D.
 
UserSetcurrentUserSet ()
 Gets the UserSet currently in effect of the camera. UserSet can access all available parameters of the camera related to 2D and 3D acquisition. UserSet can also directly set and get the parameter instead of using Parameter interface.
 
UserSetManageruserSetManager ()
 Gets the UserSetManager of the camera. UserSetManager provides various operations to manage all user set saved in the camera, including adding and deleting the user set and selecting the user set currently in effect. It is also available to save all user set details to a JSON file and read a JSON file to load user set details.
 
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 the camera side. The capture result will be obtained after the above steps are completed.
 
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 vector are computed at the camera side. The capture result will be obtained after the above steps are completed.
 
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 obtained after capturing.
 
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 the camera side. Both 2D and 3D capturing results will be obtained. This function makes it easy to get a combination of 2D and 3D data to generate textured point cloud.
 
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 are computed at the camera side. Both 2D and 3D capturing results will be obtained. This function makes it easy to get a combination of 2D and 3D data to generate textured point cloud.
 
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, LSR S, LSR L, and PRO XS.
 

Static Public Member Functions

static std::vector< CameraInfodiscoverCameras ()
 Discovers all available cameras, and returns the camera information list for them. If a camera is not successfully discovered, please check the running status and network connection of the camera.
 

Friends

class HandEyeCalibration
 
class CameraEvent
 

Detailed Description

Operates the Mech-Eye Industrial 3D Cameras. Use Camera::connect to connect an available camera, and then you can use the camera to capture 2D and 3D frames, configure parameters and so on.

Definition at line 54 of file Camera.h.

Member Function Documentation

◆ capture2D()

ErrorStatus mmind::eye::Camera::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 obtained after capturing.

Parameters
[out]frame2DThe capture result. See Frame2D for details.
[in]timeoutMsThe timeout for capturing in milliseconds. If the execution time of the capturing process is greater than the timeout, the function will immediately return ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.
ErrorStatus::MMIND_STATUS_NO_DATA_ERROR No frame data obtained. Some error may have occurred on the device.
ErrorStatus::MMIND_STATUS_NO_SUPPORT_ERROR Not supported camera model.
ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR Timeout error.

◆ capture2DAnd3D()

ErrorStatus mmind::eye::Camera::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 the camera side. Both 2D and 3D capturing results will be obtained. This function makes it easy to get a combination of 2D and 3D data to generate textured point cloud.

Parameters
[out]frame2DAnd3DThe capture result containing Frame2D and Frame3D. See Frame2DAnd3D for details.
[in]timeoutMsThe timeout for capturing in milliseconds. If the execution time of the capturing process is greater than the timeout, the function will immediately return ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.
ErrorStatus::MMIND_STATUS_NO_DATA_ERROR No frame data obtained. Some error may have occurred on the device.
ErrorStatus::MMIND_STATUS_NO_SUPPORT_ERROR Not supported camera model.
ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR Timeout error.

◆ capture2DAnd3DWithNormal()

ErrorStatus mmind::eye::Camera::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 are computed at the camera side. Both 2D and 3D capturing results will be obtained. This function makes it easy to get a combination of 2D and 3D data to generate textured point cloud.

Parameters
[out]frame2DAnd3DThe capture result containing Frame2D and Frame3D. See Frame2DAnd3D for details.
[in]timeoutMsThe timeout for capturing in milliseconds. If the execution time of the capturing process is greater than the timeout, the function will immediately return ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.
ErrorStatus::MMIND_STATUS_NO_DATA_ERROR No frame data obtained. Some error may have occurred on the device.
ErrorStatus::MMIND_STATUS_NO_SUPPORT_ERROR Not supported camera model.
ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR Timeout error.

◆ capture3D()

ErrorStatus mmind::eye::Camera::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 the camera side. The capture result will be obtained after the above steps are completed.

Parameters
[out]frame3DThe capture result. See Frame3D for details.
[in]timeoutMsThe timeout for capturing in milliseconds. If the execution time of the capturing process is greater than the timeout, the function will immediately return ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.
ErrorStatus::MMIND_STATUS_NO_DATA_ERROR No frame data obtained. Some error may have occurred on the device.
ErrorStatus::MMIND_STATUS_NO_SUPPORT_ERROR Not supported camera model.
ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR Timeout error.

◆ capture3DWithNormal()

ErrorStatus mmind::eye::Camera::capture3DWithNormal ( Frame3D frame3D,
unsigned int  timeoutMs = 10000 
) const

Projects structured light and captures a single 3D frame of the scene. 3D information and normal vector are computed at the camera side. The capture result will be obtained after the above steps are completed.

Parameters
[out]frame3DThe capture result. See Frame3D for details.
[in]timeoutMsThe timeout for capturing in milliseconds. If the execution time of the capturing process is greater than the timeout, the function will immediately return ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.
ErrorStatus::MMIND_STATUS_NO_DATA_ERROR No frame data obtained. Some error may have occurred on the device.
ErrorStatus::MMIND_STATUS_NO_SUPPORT_ERROR Not supported camera model.
ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR Timeout error.

◆ captureStereo2D()

ErrorStatus mmind::eye::Camera::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, LSR S, LSR L, and PRO XS.

Since
V2.2.1
Parameters
[out]leftThe 2D image of the left 2D camera. See Frame2D for details.
[out]rightThe 2D image of the right 2D camera. See Frame2D for details.
[in]isRectifiedWhether to perform stereo rectification. After the rectification, The left image and the depth map are aligned pixel-to-pixel. If true, the rectified 2D images are returned. If false, the origin images are returned.
[in]timeoutMsThe timeout period for capturing in milliseconds. If no data is received within the timeout period, the function will return the error code ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.
ErrorStatus::MMIND_STATUS_NO_DATA_ERROR No frame data obtained. Some error may have occurred on the device.
ErrorStatus::MMIND_STATUS_NO_SUPPORT_ERROR Not supported camera model or firmware version.
ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR Timeout error.
Note
In order to adjust the exposure effect of the stereo 2D images, different models of cameras have different adjustment parameters. For DEEP, LSR S, LSR L camera models, DepthSourceExposureMode and DepthSourceExposureTime are used, while other camera models use ExposureMode and ExposureTime.

◆ connect() [1/2]

ErrorStatus mmind::eye::Camera::connect ( const CameraInfo info,
unsigned int  timeoutMs = 5000 
)

Connects to a camera via CameraInfo.

Parameters
[in]infoThe camera information. You can use Camera::discoverCameras to find all available cameras.
[in]timeoutMsThe timeout for connecting a camera in ms unit. If the execution time of the connecting process is greater than the timeout, the function will immediately return ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_INPUT_ERROR IP address format error.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE IP address not corresponding to an available device.
ErrorStatus::MMIND_STATUS_NO_SUPPORT_ERROR Not supported camera model or firmware version.
ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR Timeout error.

◆ connect() [2/2]

ErrorStatus mmind::eye::Camera::connect ( const std::string &  ipAddress,
unsigned int  timeoutMs = 5000 
)

Connects to a camera via IP address.

Parameters
[in]ipAddressValid IP address of the camera, e.g. in "100.100.1.1" format.
[in]timeoutMsThe timeout for connecting a camera in ms unit. If the execution time of the connecting process is greater than the timeout, the function will immediately return with ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_INPUT_ERROR IP address format error.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE IP address not corresponding to an available device.
ErrorStatus::MMIND_STATUS_NO_SUPPORT_ERROR Not supported camera model or firmware version.
ErrorStatus::MMIND_STATUS_TIMEOUT_ERROR Timeout error.

◆ currentUserSet()

UserSet & mmind::eye::Camera::currentUserSet ( )

Gets the UserSet currently in effect of the camera. UserSet can access all available parameters of the camera related to 2D and 3D acquisition. UserSet can also directly set and get the parameter instead of using Parameter interface.

Returns
See UserSet for details.

◆ discoverCameras()

static std::vector< CameraInfo > mmind::eye::Camera::discoverCameras ( )
static

Discovers all available cameras, and returns the camera information list for them. If a camera is not successfully discovered, please check the running status and network connection of the camera.

Returns
The available camera information list.

◆ getCameraInfo()

ErrorStatus mmind::eye::Camera::getCameraInfo ( CameraInfo info) const

Gets the basic information of the camera, such as camera model, camera serial number, firmware version, and IP setting, etc.

Parameters
[out]SeeCameraInfo for details.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.

◆ getCameraIntrinsics()

ErrorStatus mmind::eye::Camera::getCameraIntrinsics ( CameraIntrinsics intrinsics) const

Gets the camera intrinsics. The camera intrinsics contain the texture camera intrinsics and the depth camera intrinsics based on the pinhole camera model, which correspond to the 2D and 3D scanning results Frame2D and Frame3D. The camera intrinsics also contain the transformation relationship between depth camera and texture camera.

Parameters
[out]SeeCameraIntrinsics for details.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.

◆ getCameraResolutions()

ErrorStatus mmind::eye::Camera::getCameraResolutions ( CameraResolutions resolutions) const

Gets the resolutions information of the camera. The resolutions consists of two parts, texture and depth, which correspond to the 2D and 3D scanning results Frame2D and Frame3D.

Parameters
[out]SeeCameraResolutions for details.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.

◆ getCameraStatus()

ErrorStatus mmind::eye::Camera::getCameraStatus ( CameraStatus status) const

Gets the running status of the camera.

Parameters
[out]SeeCameraStatus for details.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.

◆ setHeartbeatInterval()

ErrorStatus mmind::eye::Camera::setHeartbeatInterval ( unsigned int  timeIntervalMs)

Sets the time interval at which the client sends periodic heartbeat messages to the camera side. The default time interval is 10s.

Parameters
[in]timeIntervalMsThe time interval for periodic sending heartbeat messages in milliseconds. The valid setting range is from 1s to 3600s.
Returns
ErrorStatus::MMIND_STATUS_SUCCESS Success.
ErrorStatus::MMIND_STATUS_INVALID_DEVICE Invalid camera handle.
ErrorStatus::MMIND_STATUS_DEVICE_OFFLINE Camera disconnected.
ErrorStatus::MMIND_STATUS_OUT_OF_RANGE_ERROR Invalid parameter input.

◆ userSetManager()

UserSetManager & mmind::eye::Camera::userSetManager ( )

Gets the UserSetManager of the camera. UserSetManager provides various operations to manage all user set saved in the camera, including adding and deleting the user set and selecting the user set currently in effect. It is also available to save all user set details to a JSON file and read a JSON file to load user set details.

Returns
See UserSetManager for details.

Friends And Related Symbol Documentation

◆ CameraEvent

friend class CameraEvent
friend

Definition at line 333 of file Camera.h.

◆ HandEyeCalibration

friend class HandEyeCalibration
friend

Definition at line 332 of file Camera.h.


The documentation for this class was generated from the following file: