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) { \
79 bool bUsesImageFormats;
81 int nImgFmtDefaultNormal;
83 int nImgFmtDefaultTrigger;
89 typedef struct _UEYE_IMAGE
95 } UEYE_IMAGE, *PUEYE_IMAGE;
97 class vpUeyeGrabber::vpUeyeGrabberImpl
101 : m_hCamera((HIDS)0), m_activeCameraSelected(-1), m_pLastBuffer(nullptr), m_cameraList(nullptr), m_bLive(true),
102 m_bLiveStarted(false), m_verbose(false), m_I_temp()
104 ZeroMemory(&m_SensorInfo,
sizeof(SENSORINFO));
105 ZeroMemory(&m_CamInfo,
sizeof(CAMINFO));
106 ZeroMemory(&m_CamListInfo,
sizeof(UEYE_CAMERA_INFO));
107 ZeroMemory(m_Images,
sizeof(m_Images));
109 m_BufferProps.width = 0;
110 m_BufferProps.height = 0;
111 m_BufferProps.bitspp = 8;
122 ~vpUeyeGrabberImpl() { close(); }
126 INT ret = IS_SUCCESS;
134 ret = is_FreezeVideo(m_hCamera, IS_WAIT);
137 if (!m_bLiveStarted) {
138 ret = is_CaptureVideo(m_hCamera, IS_DONT_WAIT);
139 m_bLiveStarted =
true;
145 if (ret == IS_SUCCESS) {
147 char *pLast =
nullptr, *pMem =
nullptr;
149 is_GetActSeqBuf(m_hCamera, &dummy, &pMem, &pLast);
150 m_pLastBuffer = pLast;
152 if (!m_pLastBuffer || m_BufferProps.width < 1 || m_BufferProps.height < 1)
155 int nNum = getImageNum(m_pLastBuffer);
156 if (timestamp_camera !=
nullptr || timestamp_system !=
nullptr) {
157 int nImageID = getImageID(m_pLastBuffer);
158 UEYEIMAGEINFO ImageInfo;
159 if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo,
sizeof(ImageInfo)) == IS_SUCCESS) {
160 if (timestamp_camera !=
nullptr) {
161 *timestamp_camera =
static_cast<double>(ImageInfo.u64TimestampDevice) / 10000.;
163 if (timestamp_system !=
nullptr) {
164 std::stringstream ss;
165 ss << ImageInfo.TimestampSystem.wYear <<
":" << std::setfill(
'0') << std::setw(2)
166 << ImageInfo.TimestampSystem.wMonth <<
":" << std::setfill(
'0') << std::setw(2)
167 << ImageInfo.TimestampSystem.wDay <<
":" << std::setfill(
'0') << std::setw(2)
168 << ImageInfo.TimestampSystem.wHour <<
":" << std::setfill(
'0') << std::setw(2)
169 << ImageInfo.TimestampSystem.wMinute <<
":" << std::setfill(
'0') << std::setw(2)
170 << ImageInfo.TimestampSystem.wSecond <<
":" << std::setfill(
'0') << std::setw(3)
171 << ImageInfo.TimestampSystem.wMilliseconds;
172 *timestamp_system = ss.str();
177 helper::LockUnlockSeqBuffer lock(m_hCamera, nNum, m_pLastBuffer);
179 if (lock.OwnsLock()) {
181 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
186 memcpy(
reinterpret_cast<unsigned char *
>(I.
bitmap),
reinterpret_cast<unsigned char *
>(m_pLastBuffer),
187 m_BufferProps.width * m_BufferProps.height * m_BufferProps.bitspp / 8);
189 case IS_CM_SENSOR_RAW8:
190 m_I_temp.resize(m_BufferProps.height, m_BufferProps.width),
192 reinterpret_cast<unsigned char *
>(m_I_temp.bitmap),
193 m_BufferProps.width, m_BufferProps.height);
195 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
196 m_BufferProps.height);
198 case IS_CM_BGR565_PACKED:
201 case IS_CM_RGB8_PACKED:
203 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
204 m_BufferProps.height);
206 case IS_CM_BGR8_PACKED:
208 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
209 m_BufferProps.height);
211 case IS_CM_RGBA8_PACKED:
213 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
214 m_BufferProps.height);
216 case IS_CM_BGRA8_PACKED:
218 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
219 m_BufferProps.height);
229 INT ret = IS_SUCCESS;
237 ret = is_FreezeVideo(m_hCamera, IS_WAIT);
240 if (!m_bLiveStarted) {
242 ret = is_CaptureVideo(m_hCamera, IS_WAIT);
243 m_bLiveStarted =
true;
249 if (ret == IS_SUCCESS) {
251 char *pLast =
nullptr, *pMem =
nullptr;
253 is_GetActSeqBuf(m_hCamera, &dummy, &pMem, &pLast);
254 m_pLastBuffer = pLast;
256 if (!m_pLastBuffer || m_BufferProps.width < 1 || m_BufferProps.height < 1)
259 int nNum = getImageNum(m_pLastBuffer);
260 if (timestamp_camera !=
nullptr || timestamp_system !=
nullptr) {
261 int nImageID = getImageID(m_pLastBuffer);
262 UEYEIMAGEINFO ImageInfo;
263 if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo,
sizeof(ImageInfo)) == IS_SUCCESS) {
264 if (timestamp_camera !=
nullptr) {
265 *timestamp_camera =
static_cast<double>(ImageInfo.u64TimestampDevice) / 10000.;
267 if (timestamp_system !=
nullptr) {
268 std::stringstream ss;
269 ss << ImageInfo.TimestampSystem.wYear <<
":" << std::setfill(
'0') << std::setw(2)
270 << ImageInfo.TimestampSystem.wMonth <<
":" << std::setfill(
'0') << std::setw(2)
271 << ImageInfo.TimestampSystem.wDay <<
":" << std::setfill(
'0') << std::setw(2)
272 << ImageInfo.TimestampSystem.wHour <<
":" << std::setfill(
'0') << std::setw(2)
273 << ImageInfo.TimestampSystem.wMinute <<
":" << std::setfill(
'0') << std::setw(2)
274 << ImageInfo.TimestampSystem.wSecond <<
":" << std::setfill(
'0') << std::setw(3)
275 << ImageInfo.TimestampSystem.wMilliseconds;
276 *timestamp_system = ss.str();
281 helper::LockUnlockSeqBuffer lock(m_hCamera, nNum, m_pLastBuffer);
283 if (lock.OwnsLock()) {
285 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
291 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
292 m_BufferProps.height);
294 case IS_CM_SENSOR_RAW8:
296 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
297 m_BufferProps.height);
299 case IS_CM_BGR565_PACKED:
302 case IS_CM_RGB8_PACKED:
304 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
305 m_BufferProps.height);
307 case IS_CM_BGR8_PACKED:
309 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
310 m_BufferProps.height);
312 case IS_CM_RGBA8_PACKED:
313 memcpy(
reinterpret_cast<unsigned char *
>(I.
bitmap),
reinterpret_cast<unsigned char *
>(m_pLastBuffer),
314 m_BufferProps.width * m_BufferProps.height * m_BufferProps.bitspp / 8);
316 case IS_CM_BGRA8_PACKED:
318 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
319 m_BufferProps.height);
329 m_pLastBuffer =
nullptr;
336 is_AOI(m_hCamera, IS_AOI_IMAGE_GET_POS_X_ABS, (
void *)&nAbsPosX,
sizeof(nAbsPosX));
337 is_AOI(m_hCamera, IS_AOI_IMAGE_GET_POS_Y_ABS, (
void *)&nAbsPosY,
sizeof(nAbsPosY));
339 is_ClearSequence(m_hCamera);
342 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++) {
343 nWidth = m_BufferProps.width;
344 nHeight = m_BufferProps.height;
347 m_BufferProps.width = nWidth = m_SensorInfo.nMaxWidth;
350 m_BufferProps.height = nHeight = m_SensorInfo.nMaxHeight;
353 if (is_AllocImageMem(m_hCamera, nWidth, nHeight, m_BufferProps.bitspp, &m_Images[i].pBuf,
354 &m_Images[i].nImageID) != IS_SUCCESS)
356 if (is_AddToSequence(m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID) != IS_SUCCESS)
359 m_Images[i].nImageSeqNum = i + 1;
360 m_Images[i].nBufferSize = nWidth * nHeight * m_BufferProps.bitspp / 8;
366 int cameraInitialized()
369 unsigned int uInitialParameterSet = IS_CONFIG_INITIAL_PARAMETERSET_NONE;
371 if ((ret = is_GetCameraInfo(m_hCamera, &m_CamInfo)) != IS_SUCCESS) {
374 else if ((ret = is_GetSensorInfo(m_hCamera, &m_SensorInfo)) != IS_SUCCESS) {
377 else if ((ret = is_Configuration(IS_CONFIG_INITIAL_PARAMETERSET_CMD_GET, &uInitialParameterSet,
378 sizeof(
unsigned int))) != IS_SUCCESS) {
388 if (uInitialParameterSet == IS_CONFIG_INITIAL_PARAMETERSET_NONE) {
389 ret = is_ResetToDefault(m_hCamera);
393 if (m_SensorInfo.nColorMode >= IS_COLORMODE_BAYER) {
394 colormode = IS_CM_BGRA8_PACKED;
397 colormode = IS_CM_MONO8;
400 if (is_SetColorMode(m_hCamera, colormode) != IS_SUCCESS) {
405 ZeroMemory(&m_CameraProps,
sizeof(m_CameraProps));
408 m_CameraProps.bUsesImageFormats =
false;
409 INT nAOISupported = 0;
410 if (is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_ARBITRARY_AOI_SUPPORTED, (
void *)&nAOISupported,
411 sizeof(nAOISupported)) == IS_SUCCESS) {
412 m_CameraProps.bUsesImageFormats = (nAOISupported == 0);
416 if (m_CameraProps.bUsesImageFormats) {
418 m_CameraProps.nImgFmtNormal = searchDefImageFormats(CAPTMODE_FREERUN | CAPTMODE_SINGLE);
419 m_CameraProps.nImgFmtDefaultNormal = m_CameraProps.nImgFmtNormal;
420 m_CameraProps.nImgFmtTrigger = searchDefImageFormats(CAPTMODE_TRIGGER_SOFT_SINGLE);
421 m_CameraProps.nImgFmtDefaultTrigger = m_CameraProps.nImgFmtTrigger;
423 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_SET_FORMAT, (
void *)&m_CameraProps.nImgFmtNormal,
424 sizeof(m_CameraProps.nImgFmtNormal))) == IS_SUCCESS) {
433 enableEvent(IS_SET_EVENT_FRAME);
436 m_pLastBuffer =
nullptr;
443 if (m_hCamera == IS_INVALID_HIDS)
447 if (m_bLive && m_bLiveStarted) {
451 nRet = is_StopLiveVideo(m_hCamera, IS_WAIT);
453 m_bLiveStarted =
false;
456 is_ClearSequence(m_hCamera);
459 if (is_ExitCamera(m_hCamera) != IS_SUCCESS) {
471 is_DisableEvent(m_hCamera, m_event);
473 is_ExitEvent(m_hCamera, m_event);
474 CloseHandle(m_hEvent);
478 int enableEvent(
int event)
483 m_hEvent = CreateEvent(
nullptr, FALSE, FALSE,
nullptr);
484 if (m_hEvent ==
nullptr) {
487 ret = is_InitEvent(m_hCamera, m_hEvent, m_event);
489 ret = is_EnableEvent(m_hCamera, m_event);
497 if (is_WaitEvent(m_hCamera, m_event, EVENTTHREAD_WAIT_TIMEOUT) == IS_SUCCESS) {
499 if (WaitForSingleObject(m_hEvent, EVENTTHREAD_WAIT_TIMEOUT) == WAIT_OBJECT_0) {
510 m_pLastBuffer =
nullptr;
512 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++) {
513 if (
nullptr != m_Images[i].pBuf) {
514 is_FreeImageMem(m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID);
517 m_Images[i].pBuf =
nullptr;
518 m_Images[i].nImageID = 0;
519 m_Images[i].nImageSeqNum = 0;
527 int getBitsPerPixel(
int colormode)
532 case IS_CM_SENSOR_RAW8:
536 case IS_CM_SENSOR_RAW12:
537 case IS_CM_SENSOR_RAW16:
538 case IS_CM_BGR5_PACKED:
539 case IS_CM_BGR565_PACKED:
540 case IS_CM_UYVY_PACKED:
541 case IS_CM_CBYCRY_PACKED:
543 case IS_CM_RGB8_PACKED:
544 case IS_CM_BGR8_PACKED:
546 case IS_CM_RGBA8_PACKED:
547 case IS_CM_BGRA8_PACKED:
548 case IS_CM_RGBY8_PACKED:
549 case IS_CM_BGRY8_PACKED:
550 case IS_CM_RGB10_PACKED:
551 case IS_CM_BGR10_PACKED:
558 CameraList camera_list;
559 return camera_list.getCameraIDList();
564 CameraList camera_list;
565 return camera_list.getCameraModelList();
570 CameraList camera_list;
571 return camera_list.getCameraSerialNumberList();
579 return static_cast<unsigned int>(m_BufferProps.height);
587 return static_cast<unsigned int>(m_BufferProps.width);
598 if (is_GetFramesPerSecond(m_hCamera, &fps) != IS_SUCCESS) {
600 std::cout <<
"Unable to get acquisition frame rate" << std::endl;
606 INT getImageID(
char *pbuf)
611 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++)
612 if (m_Images[i].pBuf == pbuf)
613 return m_Images[i].nImageID;
618 INT getImageNum(
char *pbuf)
623 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++)
624 if (m_Images[i].pBuf == pbuf)
625 return m_Images[i].nImageSeqNum;
630 bool isConnected()
const {
return (m_hCamera != (HIDS)0); }
638 const std::wstring filename_(filename.begin(), filename.end());
639 int ret = is_ParameterSet(m_hCamera, IS_PARAMETERSET_CMD_LOAD_FILE, (
void *)filename_.c_str(), 0);
641 if (ret == IS_INVALID_CAMERA_TYPE) {
645 else if (ret == IS_INCOMPATIBLE_SETTING) {
647 "Because of incompatible settings, cannot load parameters from file %s", filename.c_str()));
649 else if (ret != IS_SUCCESS) {
653 std::cout <<
"Parameters loaded sucessfully" << std::endl;
662 if (is_ExitCamera(m_hCamera) != IS_SUCCESS) {
668 m_hCamera = (HIDS)(m_CamListInfo.dwDeviceID | IS_USE_DEVICE_ID);
670 if (is_InitCamera(&m_hCamera, 0) != IS_SUCCESS) {
674 int ret = cameraInitialized();
675 if (ret != IS_SUCCESS) {
683 I.
resize(m_SensorInfo.nMaxHeight, m_SensorInfo.nMaxWidth);
691 int searchDefImageFormats(
int suppportMask)
693 int ret = IS_SUCCESS;
696 IMAGE_FORMAT_LIST *pFormatList;
699 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_NUM_ENTRIES, (
void *)&nNumber,
sizeof(nNumber))) ==
701 (ret = is_AOI(m_hCamera, IS_AOI_IMAGE_GET_AOI, (
void *)&rectAOI,
sizeof(rectAOI))) == IS_SUCCESS) {
703 int nSize =
sizeof(IMAGE_FORMAT_LIST) + (nNumber - 1) *
sizeof(IMAGE_FORMAT_LIST);
704 pFormatList = (IMAGE_FORMAT_LIST *)(
new char[nSize]);
705 pFormatList->nNumListElements = nNumber;
706 pFormatList->nSizeOfListEntry =
sizeof(IMAGE_FORMAT_INFO);
708 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_LIST, (
void *)pFormatList, nSize)) == IS_SUCCESS) {
709 for (i = 0; i < nNumber; i++) {
710 if ((pFormatList->FormatInfo[i].nSupportedCaptureModes & suppportMask) &&
711 pFormatList->FormatInfo[i].nHeight == (UINT)rectAOI.s32Height &&
712 pFormatList->FormatInfo[i].nWidth == (UINT)rectAOI.s32Width) {
713 format = pFormatList->FormatInfo[i].nFormatID;
722 delete (pFormatList);
732 m_cameraList =
new CameraList;
733 m_activeCameraSelected = m_cameraList->setActiveCamera(cam_index);
734 if (!m_activeCameraSelected) {
735 m_CamListInfo = m_cameraList->getCameraInfo();
738 return m_activeCameraSelected;
741 std::string toUpper(
const std::basic_string<char> &s)
743 std::string s_upper = s;
744 for (std::basic_string<char>::iterator p = s_upper.begin(); p != s_upper.end(); ++p) {
754 "Cannot set color mode. Connection to active uEye camera is not opened"));
757 std::string color_mode_upper = toUpper(color_mode);
758 int cm = IS_CM_MONO8;
759 if (color_mode_upper ==
"MONO8") {
762 else if (color_mode_upper ==
"RGB24") {
763 cm = IS_CM_BGR8_PACKED;
765 else if (color_mode_upper ==
"RGB32") {
766 cm = IS_CM_RGBA8_PACKED;
768 else if (color_mode_upper ==
"BAYER8") {
769 cm = IS_CM_SENSOR_RAW8;
775 INT ret = IS_SUCCESS;
776 if ((ret = is_SetColorMode(m_hCamera, cm)) != IS_SUCCESS) {
777 std::cout <<
"Could not set color mode of " << m_CamListInfo.Model <<
" to " << color_mode << std::endl;
785 int setFrameRate(
bool auto_frame_rate,
double frame_rate_hz)
789 "Cannot set frame rate. Connection to active uEye camera is not opened"));
792 INT ret = IS_SUCCESS;
795 if (auto_frame_rate) {
796 double pval1 = 0, pval2 = 0;
799 bool autoShutterOn =
false;
800 is_SetAutoParameter(m_hCamera, IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2);
801 autoShutterOn |= (pval1 != 0);
802 is_SetAutoParameter(m_hCamera, IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2);
803 autoShutterOn |= (pval1 != 0);
804 if (!autoShutterOn) {
806 std::cout <<
"Auto shutter mode is not supported for " << m_CamListInfo.Model << std::endl;
808 return IS_NO_SUCCESS;
812 pval1 = auto_frame_rate;
813 if ((ret = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
814 if ((ret = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
816 std::cout <<
"Auto frame rate mode is not supported for " << m_CamListInfo.Model << std::endl;
818 return IS_NO_SUCCESS;
823 double minFrameTime, maxFrameTime, intervalFrameTime, newFrameRate;
825 if ((ret = is_GetFrameTimeRange(m_hCamera, &minFrameTime, &maxFrameTime, &intervalFrameTime)) != IS_SUCCESS) {
827 std::cout <<
"Failed to query valid frame rate range from " << m_CamListInfo.Model << std::endl;
831 CAP(frame_rate_hz, 1.0 / maxFrameTime, 1.0 / minFrameTime);
834 if ((ret = is_SetFrameRate(m_hCamera, frame_rate_hz, &newFrameRate)) != IS_SUCCESS) {
836 std::cout <<
"Failed to set frame rate to " << frame_rate_hz <<
" MHz for " << m_CamListInfo.Model
841 else if (frame_rate_hz != newFrameRate) {
842 frame_rate_hz = newFrameRate;
847 std::cout <<
"Updated frame rate for " << m_CamListInfo.Model <<
": "
848 << ((auto_frame_rate) ?
"auto" : std::to_string(frame_rate_hz)) <<
" Hz" << std::endl;
854 int setExposure(
bool auto_exposure,
double exposure_ms)
861 INT err = IS_SUCCESS;
863 double minExposure, maxExposure;
867 double pval1 = auto_exposure, pval2 = 0;
868 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
869 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
870 std::cout <<
"Auto exposure mode is not supported for " << m_CamListInfo.Model << std::endl;
871 return IS_NO_SUCCESS;
878 if (((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MIN, (
void *)&minExposure,
879 sizeof(minExposure))) != IS_SUCCESS) ||
880 ((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MAX, (
void *)&maxExposure,
881 sizeof(maxExposure))) != IS_SUCCESS)) {
882 std::cout <<
"Failed to query valid exposure range from " << m_CamListInfo.Model << std::endl;
885 CAP(exposure_ms, minExposure, maxExposure);
888 if ((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_SET_EXPOSURE, (
void *)&(exposure_ms),
sizeof(exposure_ms))) !=
890 std::cout <<
"Failed to set exposure to " << exposure_ms <<
" ms for " << m_CamListInfo.Model << std::endl;
896 std::cout <<
"Updated exposure: " << ((auto_exposure) ?
"auto" : std::to_string(exposure_ms) +
" ms") <<
" for "
897 << m_CamListInfo.Model << std::endl;
903 int setGain(
bool auto_gain,
int master_gain,
bool gain_boost)
909 INT err = IS_SUCCESS;
912 CAP(master_gain, 0, 100);
914 double pval1 = 0, pval2 = 0;
919 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
920 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
922 std::cout << m_CamListInfo.Model <<
" does not support auto gain mode" << std::endl;
924 return IS_NO_SUCCESS;
930 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
931 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
932 std::cout << m_CamListInfo.Model <<
" does not support auto gain mode" << std::endl;
937 if (is_SetGainBoost(m_hCamera, IS_GET_SUPPORTED_GAINBOOST) != IS_SET_GAINBOOST_ON) {
941 if ((err = is_SetGainBoost(m_hCamera, (gain_boost) ? IS_SET_GAINBOOST_ON : IS_SET_GAINBOOST_OFF)) !=
943 std::cout <<
"Failed to " << ((gain_boost) ?
"enable" :
"disable") <<
" gain boost for "
944 << m_CamListInfo.Model << std::endl;
949 if ((err = is_SetHardwareGain(m_hCamera, master_gain, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER,
950 IS_IGNORE_PARAMETER)) != IS_SUCCESS) {
951 std::cout <<
"Failed to set manual master gain: " << master_gain <<
" for " << m_CamListInfo.Model << std::endl;
952 return IS_NO_SUCCESS;
958 std::cout <<
"Updated gain for " << m_CamListInfo.Model <<
": auto" << std::endl;
961 std::cout <<
"Updated gain for " << m_CamListInfo.Model <<
": manual master gain " << master_gain << std::endl;
963 std::cout <<
"\n gain boost: " << (gain_boost ?
"enabled" :
"disabled") << std::endl;
970 void applySubsamplingSettings(
int subsamplingMode,
int nMode)
972 INT ret = IS_SUCCESS;
973 int currentSubsampling = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING);
974 if ((ret = is_SetSubSampling(m_hCamera, subsamplingMode | nMode)) != IS_SUCCESS) {
978 int newSubsampling = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING);
979 if ((nMode == IS_SUBSAMPLING_DISABLE) && (currentSubsampling == newSubsampling)) {
982 if ((ret = is_SetSubSampling(m_hCamera, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
992 "Cannot set sub sampling factor. Connection to active uEye camera is not opened"));
995 INT hMode = IS_SUBSAMPLING_DISABLE, vMode = IS_SUBSAMPLING_DISABLE;
999 hMode = IS_SUBSAMPLING_2X_HORIZONTAL;
1000 vMode = IS_SUBSAMPLING_2X_VERTICAL;
1003 hMode = IS_SUBSAMPLING_3X_HORIZONTAL;
1004 vMode = IS_SUBSAMPLING_3X_VERTICAL;
1007 hMode = IS_SUBSAMPLING_4X_HORIZONTAL;
1008 vMode = IS_SUBSAMPLING_4X_VERTICAL;
1011 hMode = IS_SUBSAMPLING_5X_HORIZONTAL;
1012 vMode = IS_SUBSAMPLING_5X_VERTICAL;
1015 hMode = IS_SUBSAMPLING_6X_HORIZONTAL;
1016 vMode = IS_SUBSAMPLING_6X_VERTICAL;
1019 hMode = IS_SUBSAMPLING_8X_HORIZONTAL;
1020 vMode = IS_SUBSAMPLING_8X_VERTICAL;
1023 hMode = IS_SUBSAMPLING_16X_HORIZONTAL;
1024 vMode = IS_SUBSAMPLING_16X_VERTICAL;
1027 hMode = IS_SUBSAMPLING_DISABLE;
1028 vMode = IS_SUBSAMPLING_DISABLE;
1031 if (m_bLive && m_bLiveStarted) {
1032 is_StopLiveVideo(m_hCamera, IS_WAIT);
1035 INT subsamplingModeH = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING) & IS_SUBSAMPLING_MASK_VERTICAL;
1036 applySubsamplingSettings(subsamplingModeH, hMode);
1038 INT subsamplingModeV = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING) & IS_SUBSAMPLING_MASK_HORIZONTAL;
1039 applySubsamplingSettings(subsamplingModeV, vMode);
1048 "Cannot set white balance. Connection to active uEye camera is not opened"));
1051 double dblAutoWb = 0.0;
1055 is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb,
nullptr);
1058 is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb,
nullptr);
1062 is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb,
nullptr);
1063 is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb,
nullptr);
1071 ZeroMemory(&m_BufferProps,
sizeof(m_BufferProps));
1074 INT nRet = is_AOI(m_hCamera, IS_AOI_IMAGE_GET_AOI, (
void *)&rectAOI,
sizeof(rectAOI));
1076 if (nRet == IS_SUCCESS) {
1077 width = rectAOI.s32Width;
1078 height = rectAOI.s32Height;
1081 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
1083 if (colormode == IS_CM_BGR5_PACKED) {
1084 is_SetColorMode(m_hCamera, IS_CM_BGR565_PACKED);
1085 colormode = IS_CM_BGR565_PACKED;
1086 std::cout <<
"uEye color format 'IS_CM_BGR5_PACKED' actually not supported by vpUeyeGrabber, patched to "
1087 "'IS_CM_BGR565_PACKED'"
1092 ZeroMemory(&m_BufferProps,
sizeof(m_BufferProps));
1093 m_BufferProps.width = width;
1094 m_BufferProps.height = height;
1095 m_BufferProps.bitspp = getBitsPerPixel(colormode);
1101 std::cout <<
"Capture ready set up." << std::endl;
1107 void setVerbose(
bool verbose) { m_verbose = verbose; }
1111 int m_activeCameraSelected;
1112 SENSORINFO m_SensorInfo;
1114 UEYE_CAMERA_INFO m_CamListInfo;
1115 char *m_pLastBuffer;
1116 CameraList *m_cameraList;
1117 struct sBufferProps m_BufferProps;
1118 struct sCameraProps m_CameraProps;
1119 UEYE_IMAGE m_Images[IMAGE_COUNT];
1121 bool m_bLiveStarted;
1172 m_impl->acquire(I, timestamp_camera, timestamp_system);
1197 m_impl->acquire(I, timestamp_camera, timestamp_system);
1241 return m_impl->getCameraSerialNumberList();
1301 return (m_impl->setActiveCamera(cam_index) ?
false :
true);
1321 return (m_impl->setColorMode(color_mode) ?
false :
true);
1339 return (m_impl->setExposure(auto_exposure, exposure_ms) ?
false :
true);
1374 return (m_impl->setFrameRate(auto_frame_rate, manual_frame_rate_hz) ?
false :
true);
1395 return (m_impl->setGain(auto_gain, master_gain, gain_boost) ?
false :
true);
1429 #elif !defined(VISP_BUILD_SHARED_LIBS)
1431 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()