36 #include <visp3/core/vpConfig.h>
38 #if defined(VISP_HAVE_UEYE)
42 #include <visp3/core/vpImageConvert.h>
43 #include <visp3/core/vpIoTools.h>
44 #include <visp3/sensor/vpUeyeGrabber.h>
48 #include "vpUeyeGrabber_impl.h"
50 #ifndef DOXYGEN_SHOULD_SKIP_THIS
56 #define CAMINFO BOARDINFO
57 #define EVENTTHREAD_WAIT_TIMEOUT 1000
59 #define CAP(val, min, max) \
63 } else if (val > max) { \
80 bool bUsesImageFormats;
82 int nImgFmtDefaultNormal;
84 int nImgFmtDefaultTrigger;
90 typedef struct _UEYE_IMAGE
96 } UEYE_IMAGE, *PUEYE_IMAGE;
98 class vpUeyeGrabber::vpUeyeGrabberImpl
102 : m_hCamera((HIDS)0), m_activeCameraSelected(-1), m_pLastBuffer(nullptr), m_cameraList(nullptr), m_bLive(true),
103 m_bLiveStarted(false), m_verbose(false), m_I_temp()
105 ZeroMemory(&m_SensorInfo,
sizeof(SENSORINFO));
106 ZeroMemory(&m_CamInfo,
sizeof(CAMINFO));
107 ZeroMemory(&m_CamListInfo,
sizeof(UEYE_CAMERA_INFO));
108 ZeroMemory(m_Images,
sizeof(m_Images));
110 m_BufferProps.width = 0;
111 m_BufferProps.height = 0;
112 m_BufferProps.bitspp = 8;
123 ~vpUeyeGrabberImpl() { close(); }
127 INT ret = IS_SUCCESS;
135 ret = is_FreezeVideo(m_hCamera, IS_WAIT);
138 if (!m_bLiveStarted) {
139 ret = is_CaptureVideo(m_hCamera, IS_DONT_WAIT);
140 m_bLiveStarted =
true;
146 if (ret == IS_SUCCESS) {
148 char *pLast =
nullptr, *pMem =
nullptr;
150 is_GetActSeqBuf(m_hCamera, &dummy, &pMem, &pLast);
151 m_pLastBuffer = pLast;
153 if (!m_pLastBuffer || m_BufferProps.width < 1 || m_BufferProps.height < 1)
156 int nNum = getImageNum(m_pLastBuffer);
157 if (timestamp_camera !=
nullptr || timestamp_system !=
nullptr) {
158 int nImageID = getImageID(m_pLastBuffer);
159 UEYEIMAGEINFO ImageInfo;
160 if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo,
sizeof(ImageInfo)) == IS_SUCCESS) {
161 if (timestamp_camera !=
nullptr) {
162 *timestamp_camera =
static_cast<double>(ImageInfo.u64TimestampDevice) / 10000.;
164 if (timestamp_system !=
nullptr) {
165 std::stringstream ss;
166 ss << ImageInfo.TimestampSystem.wYear <<
":" << std::setfill(
'0') << std::setw(2)
167 << ImageInfo.TimestampSystem.wMonth <<
":" << std::setfill(
'0') << std::setw(2)
168 << ImageInfo.TimestampSystem.wDay <<
":" << std::setfill(
'0') << std::setw(2)
169 << ImageInfo.TimestampSystem.wHour <<
":" << std::setfill(
'0') << std::setw(2)
170 << ImageInfo.TimestampSystem.wMinute <<
":" << std::setfill(
'0') << std::setw(2)
171 << ImageInfo.TimestampSystem.wSecond <<
":" << std::setfill(
'0') << std::setw(3)
172 << ImageInfo.TimestampSystem.wMilliseconds;
173 *timestamp_system = ss.str();
178 helper::LockUnlockSeqBuffer lock(m_hCamera, nNum, m_pLastBuffer);
180 if (lock.OwnsLock()) {
182 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
187 memcpy(
reinterpret_cast<unsigned char *
>(I.
bitmap),
reinterpret_cast<unsigned char *
>(m_pLastBuffer),
188 m_BufferProps.width * m_BufferProps.height * m_BufferProps.bitspp / 8);
190 case IS_CM_SENSOR_RAW8:
191 m_I_temp.resize(m_BufferProps.height, m_BufferProps.width),
193 reinterpret_cast<unsigned char *
>(m_I_temp.bitmap),
194 m_BufferProps.width, m_BufferProps.height);
196 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
197 m_BufferProps.height);
199 case IS_CM_BGR565_PACKED:
202 case IS_CM_RGB8_PACKED:
204 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
205 m_BufferProps.height);
207 case IS_CM_BGR8_PACKED:
209 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
210 m_BufferProps.height);
212 case IS_CM_RGBA8_PACKED:
214 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
215 m_BufferProps.height);
217 case IS_CM_BGRA8_PACKED:
219 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
220 m_BufferProps.height);
230 INT ret = IS_SUCCESS;
238 ret = is_FreezeVideo(m_hCamera, IS_WAIT);
241 if (!m_bLiveStarted) {
243 ret = is_CaptureVideo(m_hCamera, IS_WAIT);
244 m_bLiveStarted =
true;
250 if (ret == IS_SUCCESS) {
252 char *pLast =
nullptr, *pMem =
nullptr;
254 is_GetActSeqBuf(m_hCamera, &dummy, &pMem, &pLast);
255 m_pLastBuffer = pLast;
257 if (!m_pLastBuffer || m_BufferProps.width < 1 || m_BufferProps.height < 1)
260 int nNum = getImageNum(m_pLastBuffer);
261 if (timestamp_camera !=
nullptr || timestamp_system !=
nullptr) {
262 int nImageID = getImageID(m_pLastBuffer);
263 UEYEIMAGEINFO ImageInfo;
264 if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo,
sizeof(ImageInfo)) == IS_SUCCESS) {
265 if (timestamp_camera !=
nullptr) {
266 *timestamp_camera =
static_cast<double>(ImageInfo.u64TimestampDevice) / 10000.;
268 if (timestamp_system !=
nullptr) {
269 std::stringstream ss;
270 ss << ImageInfo.TimestampSystem.wYear <<
":" << std::setfill(
'0') << std::setw(2)
271 << ImageInfo.TimestampSystem.wMonth <<
":" << std::setfill(
'0') << std::setw(2)
272 << ImageInfo.TimestampSystem.wDay <<
":" << std::setfill(
'0') << std::setw(2)
273 << ImageInfo.TimestampSystem.wHour <<
":" << std::setfill(
'0') << std::setw(2)
274 << ImageInfo.TimestampSystem.wMinute <<
":" << std::setfill(
'0') << std::setw(2)
275 << ImageInfo.TimestampSystem.wSecond <<
":" << std::setfill(
'0') << std::setw(3)
276 << ImageInfo.TimestampSystem.wMilliseconds;
277 *timestamp_system = ss.str();
282 helper::LockUnlockSeqBuffer lock(m_hCamera, nNum, m_pLastBuffer);
284 if (lock.OwnsLock()) {
286 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
292 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
293 m_BufferProps.height);
295 case IS_CM_SENSOR_RAW8:
297 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
298 m_BufferProps.height);
300 case IS_CM_BGR565_PACKED:
303 case IS_CM_RGB8_PACKED:
305 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
306 m_BufferProps.height);
308 case IS_CM_BGR8_PACKED:
310 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
311 m_BufferProps.height);
313 case IS_CM_RGBA8_PACKED:
314 memcpy(
reinterpret_cast<unsigned char *
>(I.
bitmap),
reinterpret_cast<unsigned char *
>(m_pLastBuffer),
315 m_BufferProps.width * m_BufferProps.height * m_BufferProps.bitspp / 8);
317 case IS_CM_BGRA8_PACKED:
319 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
320 m_BufferProps.height);
330 m_pLastBuffer =
nullptr;
337 is_AOI(m_hCamera, IS_AOI_IMAGE_GET_POS_X_ABS, (
void *)&nAbsPosX,
sizeof(nAbsPosX));
338 is_AOI(m_hCamera, IS_AOI_IMAGE_GET_POS_Y_ABS, (
void *)&nAbsPosY,
sizeof(nAbsPosY));
340 is_ClearSequence(m_hCamera);
343 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++) {
344 nWidth = m_BufferProps.width;
345 nHeight = m_BufferProps.height;
348 m_BufferProps.width = nWidth = m_SensorInfo.nMaxWidth;
351 m_BufferProps.height = nHeight = m_SensorInfo.nMaxHeight;
354 if (is_AllocImageMem(m_hCamera, nWidth, nHeight, m_BufferProps.bitspp, &m_Images[i].pBuf,
355 &m_Images[i].nImageID) != IS_SUCCESS)
357 if (is_AddToSequence(m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID) != IS_SUCCESS)
360 m_Images[i].nImageSeqNum = i + 1;
361 m_Images[i].nBufferSize = nWidth * nHeight * m_BufferProps.bitspp / 8;
367 int cameraInitialized()
370 unsigned int uInitialParameterSet = IS_CONFIG_INITIAL_PARAMETERSET_NONE;
372 if ((ret = is_GetCameraInfo(m_hCamera, &m_CamInfo)) != IS_SUCCESS) {
375 else if ((ret = is_GetSensorInfo(m_hCamera, &m_SensorInfo)) != IS_SUCCESS) {
378 else if ((ret = is_Configuration(IS_CONFIG_INITIAL_PARAMETERSET_CMD_GET, &uInitialParameterSet,
379 sizeof(
unsigned int))) != IS_SUCCESS) {
389 if (uInitialParameterSet == IS_CONFIG_INITIAL_PARAMETERSET_NONE) {
390 ret = is_ResetToDefault(m_hCamera);
394 if (m_SensorInfo.nColorMode >= IS_COLORMODE_BAYER) {
395 colormode = IS_CM_BGRA8_PACKED;
398 colormode = IS_CM_MONO8;
401 if (is_SetColorMode(m_hCamera, colormode) != IS_SUCCESS) {
406 ZeroMemory(&m_CameraProps,
sizeof(m_CameraProps));
409 m_CameraProps.bUsesImageFormats =
false;
410 INT nAOISupported = 0;
411 if (is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_ARBITRARY_AOI_SUPPORTED, (
void *)&nAOISupported,
412 sizeof(nAOISupported)) == IS_SUCCESS) {
413 m_CameraProps.bUsesImageFormats = (nAOISupported == 0);
417 if (m_CameraProps.bUsesImageFormats) {
419 m_CameraProps.nImgFmtNormal = searchDefImageFormats(CAPTMODE_FREERUN | CAPTMODE_SINGLE);
420 m_CameraProps.nImgFmtDefaultNormal = m_CameraProps.nImgFmtNormal;
421 m_CameraProps.nImgFmtTrigger = searchDefImageFormats(CAPTMODE_TRIGGER_SOFT_SINGLE);
422 m_CameraProps.nImgFmtDefaultTrigger = m_CameraProps.nImgFmtTrigger;
424 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_SET_FORMAT, (
void *)&m_CameraProps.nImgFmtNormal,
425 sizeof(m_CameraProps.nImgFmtNormal))) == IS_SUCCESS) {
434 enableEvent(IS_SET_EVENT_FRAME);
437 m_pLastBuffer =
nullptr;
444 if (m_hCamera == IS_INVALID_HIDS)
448 if (m_bLive && m_bLiveStarted) {
452 nRet = is_StopLiveVideo(m_hCamera, IS_WAIT);
454 m_bLiveStarted =
false;
457 is_ClearSequence(m_hCamera);
460 if (is_ExitCamera(m_hCamera) != IS_SUCCESS) {
472 is_DisableEvent(m_hCamera, m_event);
474 is_ExitEvent(m_hCamera, m_event);
475 CloseHandle(m_hEvent);
479 int enableEvent(
int event)
484 m_hEvent = CreateEvent(
nullptr, FALSE, FALSE,
nullptr);
485 if (m_hEvent ==
nullptr) {
488 ret = is_InitEvent(m_hCamera, m_hEvent, m_event);
490 ret = is_EnableEvent(m_hCamera, m_event);
498 if (is_WaitEvent(m_hCamera, m_event, EVENTTHREAD_WAIT_TIMEOUT) == IS_SUCCESS) {
500 if (WaitForSingleObject(m_hEvent, EVENTTHREAD_WAIT_TIMEOUT) == WAIT_OBJECT_0) {
511 m_pLastBuffer =
nullptr;
513 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++) {
514 if (
nullptr != m_Images[i].pBuf) {
515 is_FreeImageMem(m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID);
518 m_Images[i].pBuf =
nullptr;
519 m_Images[i].nImageID = 0;
520 m_Images[i].nImageSeqNum = 0;
528 int getBitsPerPixel(
int colormode)
533 case IS_CM_SENSOR_RAW8:
537 case IS_CM_SENSOR_RAW12:
538 case IS_CM_SENSOR_RAW16:
539 case IS_CM_BGR5_PACKED:
540 case IS_CM_BGR565_PACKED:
541 case IS_CM_UYVY_PACKED:
542 case IS_CM_CBYCRY_PACKED:
544 case IS_CM_RGB8_PACKED:
545 case IS_CM_BGR8_PACKED:
547 case IS_CM_RGBA8_PACKED:
548 case IS_CM_BGRA8_PACKED:
549 case IS_CM_RGBY8_PACKED:
550 case IS_CM_BGRY8_PACKED:
551 case IS_CM_RGB10_PACKED:
552 case IS_CM_BGR10_PACKED:
559 CameraList camera_list;
560 return camera_list.getCameraIDList();
565 CameraList camera_list;
566 return camera_list.getCameraModelList();
571 CameraList camera_list;
572 return camera_list.getCameraSerialNumberList();
580 return static_cast<unsigned int>(m_BufferProps.height);
588 return static_cast<unsigned int>(m_BufferProps.width);
599 if (is_GetFramesPerSecond(m_hCamera, &fps) != IS_SUCCESS) {
601 std::cout <<
"Unable to get acquisition frame rate" << std::endl;
607 INT getImageID(
char *pbuf)
612 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++)
613 if (m_Images[i].pBuf == pbuf)
614 return m_Images[i].nImageID;
619 INT getImageNum(
char *pbuf)
624 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++)
625 if (m_Images[i].pBuf == pbuf)
626 return m_Images[i].nImageSeqNum;
631 bool isConnected()
const {
return (m_hCamera != (HIDS)0); }
639 const std::wstring filename_(filename.begin(), filename.end());
640 int ret = is_ParameterSet(m_hCamera, IS_PARAMETERSET_CMD_LOAD_FILE, (
void *)filename_.c_str(), 0);
642 if (ret == IS_INVALID_CAMERA_TYPE) {
646 else if (ret == IS_INCOMPATIBLE_SETTING) {
648 "Because of incompatible settings, cannot load parameters from file %s", filename.c_str()));
650 else if (ret != IS_SUCCESS) {
654 std::cout <<
"Parameters loaded sucessfully" << std::endl;
663 if (is_ExitCamera(m_hCamera) != IS_SUCCESS) {
669 m_hCamera = (HIDS)(m_CamListInfo.dwDeviceID | IS_USE_DEVICE_ID);
671 if (is_InitCamera(&m_hCamera, 0) != IS_SUCCESS) {
675 int ret = cameraInitialized();
676 if (ret != IS_SUCCESS) {
684 I.
resize(m_SensorInfo.nMaxHeight, m_SensorInfo.nMaxWidth);
692 int searchDefImageFormats(
int suppportMask)
694 int ret = IS_SUCCESS;
697 IMAGE_FORMAT_LIST *pFormatList;
700 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_NUM_ENTRIES, (
void *)&nNumber,
sizeof(nNumber))) ==
702 (ret = is_AOI(m_hCamera, IS_AOI_IMAGE_GET_AOI, (
void *)&rectAOI,
sizeof(rectAOI))) == IS_SUCCESS) {
704 int nSize =
sizeof(IMAGE_FORMAT_LIST) + (nNumber - 1) *
sizeof(IMAGE_FORMAT_LIST);
705 pFormatList = (IMAGE_FORMAT_LIST *)(
new char[nSize]);
706 pFormatList->nNumListElements = nNumber;
707 pFormatList->nSizeOfListEntry =
sizeof(IMAGE_FORMAT_INFO);
709 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_LIST, (
void *)pFormatList, nSize)) == IS_SUCCESS) {
710 for (i = 0; i < nNumber; i++) {
711 if ((pFormatList->FormatInfo[i].nSupportedCaptureModes & suppportMask) &&
712 pFormatList->FormatInfo[i].nHeight == (UINT)rectAOI.s32Height &&
713 pFormatList->FormatInfo[i].nWidth == (UINT)rectAOI.s32Width) {
714 format = pFormatList->FormatInfo[i].nFormatID;
723 delete (pFormatList);
733 m_cameraList =
new CameraList;
734 m_activeCameraSelected = m_cameraList->setActiveCamera(cam_index);
735 if (!m_activeCameraSelected) {
736 m_CamListInfo = m_cameraList->getCameraInfo();
739 return m_activeCameraSelected;
742 std::string toUpper(
const std::basic_string<char> &s)
744 std::string s_upper = s;
745 for (std::basic_string<char>::iterator p = s_upper.begin(); p != s_upper.end(); ++p) {
755 "Cannot set color mode. Connection to active uEye camera is not opened"));
758 std::string color_mode_upper = toUpper(color_mode);
759 int cm = IS_CM_MONO8;
760 if (color_mode_upper ==
"MONO8") {
763 else if (color_mode_upper ==
"RGB24") {
764 cm = IS_CM_BGR8_PACKED;
766 else if (color_mode_upper ==
"RGB32") {
767 cm = IS_CM_RGBA8_PACKED;
769 else if (color_mode_upper ==
"BAYER8") {
770 cm = IS_CM_SENSOR_RAW8;
776 INT ret = IS_SUCCESS;
777 if ((ret = is_SetColorMode(m_hCamera, cm)) != IS_SUCCESS) {
778 std::cout <<
"Could not set color mode of " << m_CamListInfo.Model <<
" to " << color_mode << std::endl;
786 int setFrameRate(
bool auto_frame_rate,
double frame_rate_hz)
790 "Cannot set frame rate. Connection to active uEye camera is not opened"));
793 INT ret = IS_SUCCESS;
796 if (auto_frame_rate) {
797 double pval1 = 0, pval2 = 0;
800 bool autoShutterOn =
false;
801 is_SetAutoParameter(m_hCamera, IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2);
802 autoShutterOn |= (pval1 != 0);
803 is_SetAutoParameter(m_hCamera, IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2);
804 autoShutterOn |= (pval1 != 0);
805 if (!autoShutterOn) {
807 std::cout <<
"Auto shutter mode is not supported for " << m_CamListInfo.Model << std::endl;
809 return IS_NO_SUCCESS;
813 pval1 = auto_frame_rate;
814 if ((ret = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
815 if ((ret = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
817 std::cout <<
"Auto frame rate mode is not supported for " << m_CamListInfo.Model << std::endl;
819 return IS_NO_SUCCESS;
824 double minFrameTime, maxFrameTime, intervalFrameTime, newFrameRate;
826 if ((ret = is_GetFrameTimeRange(m_hCamera, &minFrameTime, &maxFrameTime, &intervalFrameTime)) != IS_SUCCESS) {
828 std::cout <<
"Failed to query valid frame rate range from " << m_CamListInfo.Model << std::endl;
832 CAP(frame_rate_hz, 1.0 / maxFrameTime, 1.0 / minFrameTime);
835 if ((ret = is_SetFrameRate(m_hCamera, frame_rate_hz, &newFrameRate)) != IS_SUCCESS) {
837 std::cout <<
"Failed to set frame rate to " << frame_rate_hz <<
" MHz for " << m_CamListInfo.Model
842 else if (frame_rate_hz != newFrameRate) {
843 frame_rate_hz = newFrameRate;
848 std::cout <<
"Updated frame rate for " << m_CamListInfo.Model <<
": "
849 << ((auto_frame_rate) ?
"auto" : std::to_string(frame_rate_hz)) <<
" Hz" << std::endl;
855 int setExposure(
bool auto_exposure,
double exposure_ms)
862 INT err = IS_SUCCESS;
864 double minExposure, maxExposure;
868 double pval1 = auto_exposure, pval2 = 0;
869 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
870 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
871 std::cout <<
"Auto exposure mode is not supported for " << m_CamListInfo.Model << std::endl;
872 return IS_NO_SUCCESS;
879 if (((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MIN, (
void *)&minExposure,
880 sizeof(minExposure))) != IS_SUCCESS) ||
881 ((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MAX, (
void *)&maxExposure,
882 sizeof(maxExposure))) != IS_SUCCESS)) {
883 std::cout <<
"Failed to query valid exposure range from " << m_CamListInfo.Model << std::endl;
886 CAP(exposure_ms, minExposure, maxExposure);
889 if ((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_SET_EXPOSURE, (
void *)&(exposure_ms),
sizeof(exposure_ms))) !=
891 std::cout <<
"Failed to set exposure to " << exposure_ms <<
" ms for " << m_CamListInfo.Model << std::endl;
897 std::cout <<
"Updated exposure: " << ((auto_exposure) ?
"auto" : std::to_string(exposure_ms) +
" ms") <<
" for "
898 << m_CamListInfo.Model << std::endl;
904 int setGain(
bool auto_gain,
int master_gain,
bool gain_boost)
910 INT err = IS_SUCCESS;
913 CAP(master_gain, 0, 100);
915 double pval1 = 0, pval2 = 0;
920 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
921 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
923 std::cout << m_CamListInfo.Model <<
" does not support auto gain mode" << std::endl;
925 return IS_NO_SUCCESS;
931 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
932 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
933 std::cout << m_CamListInfo.Model <<
" does not support auto gain mode" << std::endl;
938 if (is_SetGainBoost(m_hCamera, IS_GET_SUPPORTED_GAINBOOST) != IS_SET_GAINBOOST_ON) {
942 if ((err = is_SetGainBoost(m_hCamera, (gain_boost) ? IS_SET_GAINBOOST_ON : IS_SET_GAINBOOST_OFF)) !=
944 std::cout <<
"Failed to " << ((gain_boost) ?
"enable" :
"disable") <<
" gain boost for "
945 << m_CamListInfo.Model << std::endl;
950 if ((err = is_SetHardwareGain(m_hCamera, master_gain, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER,
951 IS_IGNORE_PARAMETER)) != IS_SUCCESS) {
952 std::cout <<
"Failed to set manual master gain: " << master_gain <<
" for " << m_CamListInfo.Model << std::endl;
953 return IS_NO_SUCCESS;
959 std::cout <<
"Updated gain for " << m_CamListInfo.Model <<
": auto" << std::endl;
962 std::cout <<
"Updated gain for " << m_CamListInfo.Model <<
": manual master gain " << master_gain << std::endl;
964 std::cout <<
"\n gain boost: " << (gain_boost ?
"enabled" :
"disabled") << std::endl;
971 void applySubsamplingSettings(
int subsamplingMode,
int nMode)
973 INT ret = IS_SUCCESS;
974 int currentSubsampling = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING);
975 if ((ret = is_SetSubSampling(m_hCamera, subsamplingMode | nMode)) != IS_SUCCESS) {
979 int newSubsampling = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING);
980 if ((nMode == IS_SUBSAMPLING_DISABLE) && (currentSubsampling == newSubsampling)) {
983 if ((ret = is_SetSubSampling(m_hCamera, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
993 "Cannot set sub sampling factor. Connection to active uEye camera is not opened"));
996 INT hMode = IS_SUBSAMPLING_DISABLE, vMode = IS_SUBSAMPLING_DISABLE;
1000 hMode = IS_SUBSAMPLING_2X_HORIZONTAL;
1001 vMode = IS_SUBSAMPLING_2X_VERTICAL;
1004 hMode = IS_SUBSAMPLING_3X_HORIZONTAL;
1005 vMode = IS_SUBSAMPLING_3X_VERTICAL;
1008 hMode = IS_SUBSAMPLING_4X_HORIZONTAL;
1009 vMode = IS_SUBSAMPLING_4X_VERTICAL;
1012 hMode = IS_SUBSAMPLING_5X_HORIZONTAL;
1013 vMode = IS_SUBSAMPLING_5X_VERTICAL;
1016 hMode = IS_SUBSAMPLING_6X_HORIZONTAL;
1017 vMode = IS_SUBSAMPLING_6X_VERTICAL;
1020 hMode = IS_SUBSAMPLING_8X_HORIZONTAL;
1021 vMode = IS_SUBSAMPLING_8X_VERTICAL;
1024 hMode = IS_SUBSAMPLING_16X_HORIZONTAL;
1025 vMode = IS_SUBSAMPLING_16X_VERTICAL;
1028 hMode = IS_SUBSAMPLING_DISABLE;
1029 vMode = IS_SUBSAMPLING_DISABLE;
1032 if (m_bLive && m_bLiveStarted) {
1033 is_StopLiveVideo(m_hCamera, IS_WAIT);
1036 INT subsamplingModeH = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING) & IS_SUBSAMPLING_MASK_VERTICAL;
1037 applySubsamplingSettings(subsamplingModeH, hMode);
1039 INT subsamplingModeV = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING) & IS_SUBSAMPLING_MASK_HORIZONTAL;
1040 applySubsamplingSettings(subsamplingModeV, vMode);
1049 "Cannot set white balance. Connection to active uEye camera is not opened"));
1052 double dblAutoWb = 0.0;
1056 is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb,
nullptr);
1059 is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb,
nullptr);
1063 is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb,
nullptr);
1064 is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb,
nullptr);
1072 ZeroMemory(&m_BufferProps,
sizeof(m_BufferProps));
1075 INT nRet = is_AOI(m_hCamera, IS_AOI_IMAGE_GET_AOI, (
void *)&rectAOI,
sizeof(rectAOI));
1077 if (nRet == IS_SUCCESS) {
1078 width = rectAOI.s32Width;
1079 height = rectAOI.s32Height;
1082 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
1084 if (colormode == IS_CM_BGR5_PACKED) {
1085 is_SetColorMode(m_hCamera, IS_CM_BGR565_PACKED);
1086 colormode = IS_CM_BGR565_PACKED;
1087 std::cout <<
"uEye color format 'IS_CM_BGR5_PACKED' actually not supported by vpUeyeGrabber, patched to "
1088 "'IS_CM_BGR565_PACKED'"
1093 ZeroMemory(&m_BufferProps,
sizeof(m_BufferProps));
1094 m_BufferProps.width = width;
1095 m_BufferProps.height = height;
1096 m_BufferProps.bitspp = getBitsPerPixel(colormode);
1102 std::cout <<
"Capture ready set up." << std::endl;
1108 void setVerbose(
bool verbose) { m_verbose = verbose; }
1112 int m_activeCameraSelected;
1113 SENSORINFO m_SensorInfo;
1115 UEYE_CAMERA_INFO m_CamListInfo;
1116 char *m_pLastBuffer;
1117 CameraList *m_cameraList;
1118 struct sBufferProps m_BufferProps;
1119 struct sCameraProps m_CameraProps;
1120 UEYE_IMAGE m_Images[IMAGE_COUNT];
1122 bool m_bLiveStarted;
1173 m_impl->acquire(I, timestamp_camera, timestamp_system);
1198 m_impl->acquire(I, timestamp_camera, timestamp_system);
1242 return m_impl->getCameraSerialNumberList();
1302 return (m_impl->setActiveCamera(cam_index) ?
false :
true);
1322 return (m_impl->setColorMode(color_mode) ?
false :
true);
1340 return (m_impl->setExposure(auto_exposure, exposure_ms) ?
false :
true);
1375 return (m_impl->setFrameRate(auto_frame_rate, manual_frame_rate_hz) ?
false :
true);
1396 return (m_impl->setGain(auto_gain, master_gain, gain_boost) ?
false :
true);
1430 #elif !defined(VISP_BUILD_SHARED_LIBS)
1432 void dummy_vpUeyeGrabber() { };
error that can be emitted by ViSP classes.
static void GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int width, unsigned int height)
static void RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false)
static void RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size)
static void BGRaToGrey(unsigned char *bgra, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false, unsigned int nThreads=0)
static void BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false, unsigned int nThreads=0)
static void BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
static void demosaicRGGBToRGBaBilinear(const uint8_t *rggb, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void BGRaToRGBa(unsigned char *bgra, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
Type * bitmap
points toward the bitmap
void open(vpImage< unsigned char > &I)
std::vector< std::string > getCameraSerialNumberList() const
bool setExposure(bool auto_exposure, double exposure_ms=-1)
bool setFrameRate(bool auto_frame_rate, double manual_frame_rate_hz=-1)
void setVerbose(bool verbose)
void setWhiteBalance(bool auto_wb)
bool setGain(bool auto_gain, int master_gain=-1, bool gain_boost=false)
void acquire(vpImage< unsigned char > &I, double *timestamp_camera=nullptr, std::string *timestamp_system=nullptr)
double getFramerate() const
void loadParameters(const std::string &filename)
std::vector< std::string > getCameraModelList() const
std::vector< unsigned int > getCameraIDList() const
void setSubsampling(int factor)
unsigned int getFrameHeight() const
unsigned int getFrameWidth() const
bool setActiveCamera(unsigned int cam_index)
bool setColorMode(const std::string &color_mode)
std::string getActiveCameraModel() const
std::string getActiveCameraSerialNumber() const
VISP_EXPORT double measureTimeSecond()