34#include <visp3/core/vpConfig.h>
36#if defined(VISP_HAVE_UEYE)
40#include <visp3/core/vpImageConvert.h>
41#include <visp3/core/vpIoTools.h>
42#include <visp3/sensor/vpUeyeGrabber.h>
46#include "vpUeyeGrabber_impl.h"
48#ifndef DOXYGEN_SHOULD_SKIP_THIS
54#define CAMINFO BOARDINFO
55#define EVENTTHREAD_WAIT_TIMEOUT 1000
57#define CAP(val, min, max) \
61 } else if (val > max) { \
78 bool bUsesImageFormats;
80 int nImgFmtDefaultNormal;
82 int nImgFmtDefaultTrigger;
88typedef struct _UEYE_IMAGE
94} UEYE_IMAGE, *PUEYE_IMAGE;
96class vpUeyeGrabber::vpUeyeGrabberImpl
100 : m_hCamera((HIDS)0), m_activeCameraSelected(-1), m_pLastBuffer(nullptr), m_cameraList(nullptr), m_bLive(true),
101 m_bLiveStarted(false), m_verbose(false), m_I_temp()
103 ZeroMemory(&m_SensorInfo,
sizeof(SENSORINFO));
104 ZeroMemory(&m_CamInfo,
sizeof(CAMINFO));
105 ZeroMemory(&m_CamListInfo,
sizeof(UEYE_CAMERA_INFO));
106 ZeroMemory(m_Images,
sizeof(m_Images));
108 m_BufferProps.width = 0;
109 m_BufferProps.height = 0;
110 m_BufferProps.bitspp = 8;
118 m_activeCameraSelected = setActiveCamera(0);
121 ~vpUeyeGrabberImpl() { close(); }
123 void acquire(vpImage<unsigned char> &I,
double *timestamp_camera, std::string *timestamp_system)
125 INT ret = IS_SUCCESS;
133 ret = is_FreezeVideo(m_hCamera, IS_WAIT);
136 if (!m_bLiveStarted) {
137 ret = is_CaptureVideo(m_hCamera, IS_DONT_WAIT);
138 m_bLiveStarted =
true;
144 if (ret == IS_SUCCESS) {
146 char *pLast =
nullptr, *pMem =
nullptr;
148 is_GetActSeqBuf(m_hCamera, &dummy, &pMem, &pLast);
149 m_pLastBuffer = pLast;
151 if (!m_pLastBuffer || m_BufferProps.width < 1 || m_BufferProps.height < 1)
154 int nNum = getImageNum(m_pLastBuffer);
155 if (timestamp_camera !=
nullptr || timestamp_system !=
nullptr) {
156 int nImageID = getImageID(m_pLastBuffer);
157 UEYEIMAGEINFO ImageInfo;
158 if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo,
sizeof(ImageInfo)) == IS_SUCCESS) {
159 if (timestamp_camera !=
nullptr) {
160 *timestamp_camera =
static_cast<double>(ImageInfo.u64TimestampDevice) / 10000.;
162 if (timestamp_system !=
nullptr) {
163 std::stringstream ss;
164 ss << ImageInfo.TimestampSystem.wYear <<
":" << std::setfill(
'0') << std::setw(2)
165 << ImageInfo.TimestampSystem.wMonth <<
":" << std::setfill(
'0') << std::setw(2)
166 << ImageInfo.TimestampSystem.wDay <<
":" << std::setfill(
'0') << std::setw(2)
167 << ImageInfo.TimestampSystem.wHour <<
":" << std::setfill(
'0') << std::setw(2)
168 << ImageInfo.TimestampSystem.wMinute <<
":" << std::setfill(
'0') << std::setw(2)
169 << ImageInfo.TimestampSystem.wSecond <<
":" << std::setfill(
'0') << std::setw(3)
170 << ImageInfo.TimestampSystem.wMilliseconds;
171 *timestamp_system = ss.str();
176 helper::LockUnlockSeqBuffer lock(m_hCamera, nNum, m_pLastBuffer);
178 if (lock.OwnsLock()) {
180 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
185 memcpy(
reinterpret_cast<unsigned char *
>(I.
bitmap),
reinterpret_cast<unsigned char *
>(m_pLastBuffer),
186 m_BufferProps.width * m_BufferProps.height * m_BufferProps.bitspp / 8);
188 case IS_CM_SENSOR_RAW8:
189 m_I_temp.resize(m_BufferProps.height, m_BufferProps.width),
191 reinterpret_cast<unsigned char *
>(m_I_temp.bitmap),
192 m_BufferProps.width, m_BufferProps.height);
194 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
195 m_BufferProps.height);
197 case IS_CM_BGR565_PACKED:
200 case IS_CM_RGB8_PACKED:
202 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
203 m_BufferProps.height);
205 case IS_CM_BGR8_PACKED:
207 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
208 m_BufferProps.height);
210 case IS_CM_RGBA8_PACKED:
212 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
213 m_BufferProps.height);
215 case IS_CM_BGRA8_PACKED:
217 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
218 m_BufferProps.height);
226 void acquire(vpImage<vpRGBa> &I,
double *timestamp_camera, std::string *timestamp_system)
228 INT ret = IS_SUCCESS;
236 ret = is_FreezeVideo(m_hCamera, IS_WAIT);
239 if (!m_bLiveStarted) {
241 ret = is_CaptureVideo(m_hCamera, IS_WAIT);
242 m_bLiveStarted =
true;
248 if (ret == IS_SUCCESS) {
250 char *pLast =
nullptr, *pMem =
nullptr;
252 is_GetActSeqBuf(m_hCamera, &dummy, &pMem, &pLast);
253 m_pLastBuffer = pLast;
255 if (!m_pLastBuffer || m_BufferProps.width < 1 || m_BufferProps.height < 1)
258 int nNum = getImageNum(m_pLastBuffer);
259 if (timestamp_camera !=
nullptr || timestamp_system !=
nullptr) {
260 int nImageID = getImageID(m_pLastBuffer);
261 UEYEIMAGEINFO ImageInfo;
262 if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo,
sizeof(ImageInfo)) == IS_SUCCESS) {
263 if (timestamp_camera !=
nullptr) {
264 *timestamp_camera =
static_cast<double>(ImageInfo.u64TimestampDevice) / 10000.;
266 if (timestamp_system !=
nullptr) {
267 std::stringstream ss;
268 ss << ImageInfo.TimestampSystem.wYear <<
":" << std::setfill(
'0') << std::setw(2)
269 << ImageInfo.TimestampSystem.wMonth <<
":" << std::setfill(
'0') << std::setw(2)
270 << ImageInfo.TimestampSystem.wDay <<
":" << std::setfill(
'0') << std::setw(2)
271 << ImageInfo.TimestampSystem.wHour <<
":" << std::setfill(
'0') << std::setw(2)
272 << ImageInfo.TimestampSystem.wMinute <<
":" << std::setfill(
'0') << std::setw(2)
273 << ImageInfo.TimestampSystem.wSecond <<
":" << std::setfill(
'0') << std::setw(3)
274 << ImageInfo.TimestampSystem.wMilliseconds;
275 *timestamp_system = ss.str();
280 helper::LockUnlockSeqBuffer lock(m_hCamera, nNum, m_pLastBuffer);
282 if (lock.OwnsLock()) {
284 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
290 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
291 m_BufferProps.height);
293 case IS_CM_SENSOR_RAW8:
295 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
296 m_BufferProps.height);
298 case IS_CM_BGR565_PACKED:
301 case IS_CM_RGB8_PACKED:
303 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
304 m_BufferProps.height);
306 case IS_CM_BGR8_PACKED:
308 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
309 m_BufferProps.height);
311 case IS_CM_RGBA8_PACKED:
312 memcpy(
reinterpret_cast<unsigned char *
>(I.
bitmap),
reinterpret_cast<unsigned char *
>(m_pLastBuffer),
313 m_BufferProps.width * m_BufferProps.height * m_BufferProps.bitspp / 8);
315 case IS_CM_BGRA8_PACKED:
317 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
318 m_BufferProps.height);
328 m_pLastBuffer =
nullptr;
335 is_AOI(m_hCamera, IS_AOI_IMAGE_GET_POS_X_ABS, (
void *)&nAbsPosX,
sizeof(nAbsPosX));
336 is_AOI(m_hCamera, IS_AOI_IMAGE_GET_POS_Y_ABS, (
void *)&nAbsPosY,
sizeof(nAbsPosY));
338 is_ClearSequence(m_hCamera);
341 for (
unsigned int i = 0;
i <
sizeof(m_Images) /
sizeof(m_Images[0]);
i++) {
342 nWidth = m_BufferProps.width;
343 nHeight = m_BufferProps.height;
346 m_BufferProps.width = nWidth = m_SensorInfo.nMaxWidth;
349 m_BufferProps.height = nHeight = m_SensorInfo.nMaxHeight;
352 if (is_AllocImageMem(m_hCamera, nWidth, nHeight, m_BufferProps.bitspp, &m_Images[i].pBuf,
353 &m_Images[i].nImageID) != IS_SUCCESS)
355 if (is_AddToSequence(m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID) != IS_SUCCESS)
358 m_Images[
i].nImageSeqNum =
i + 1;
359 m_Images[
i].nBufferSize = nWidth * nHeight * m_BufferProps.bitspp / 8;
365 int cameraInitialized()
368 unsigned int uInitialParameterSet = IS_CONFIG_INITIAL_PARAMETERSET_NONE;
370 if ((ret = is_GetCameraInfo(m_hCamera, &m_CamInfo)) != IS_SUCCESS) {
373 else if ((ret = is_GetSensorInfo(m_hCamera, &m_SensorInfo)) != IS_SUCCESS) {
376 else if ((ret = is_Configuration(IS_CONFIG_INITIAL_PARAMETERSET_CMD_GET, &uInitialParameterSet,
377 sizeof(
unsigned int))) != IS_SUCCESS) {
387 if (uInitialParameterSet == IS_CONFIG_INITIAL_PARAMETERSET_NONE) {
388 ret = is_ResetToDefault(m_hCamera);
392 if (m_SensorInfo.nColorMode >= IS_COLORMODE_BAYER) {
393 colormode = IS_CM_BGRA8_PACKED;
396 colormode = IS_CM_MONO8;
399 if (is_SetColorMode(m_hCamera, colormode) != IS_SUCCESS) {
404 ZeroMemory(&m_CameraProps,
sizeof(m_CameraProps));
407 m_CameraProps.bUsesImageFormats =
false;
408 INT nAOISupported = 0;
409 if (is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_ARBITRARY_AOI_SUPPORTED, (
void *)&nAOISupported,
410 sizeof(nAOISupported)) == IS_SUCCESS) {
411 m_CameraProps.bUsesImageFormats = (nAOISupported == 0);
415 if (m_CameraProps.bUsesImageFormats) {
417 m_CameraProps.nImgFmtNormal = searchDefImageFormats(CAPTMODE_FREERUN | CAPTMODE_SINGLE);
418 m_CameraProps.nImgFmtDefaultNormal = m_CameraProps.nImgFmtNormal;
419 m_CameraProps.nImgFmtTrigger = searchDefImageFormats(CAPTMODE_TRIGGER_SOFT_SINGLE);
420 m_CameraProps.nImgFmtDefaultTrigger = m_CameraProps.nImgFmtTrigger;
422 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_SET_FORMAT, (
void *)&m_CameraProps.nImgFmtNormal,
423 sizeof(m_CameraProps.nImgFmtNormal))) == IS_SUCCESS) {
432 enableEvent(IS_SET_EVENT_FRAME);
435 m_pLastBuffer =
nullptr;
442 if (m_hCamera == IS_INVALID_HIDS)
446 if (m_bLive && m_bLiveStarted) {
450 nRet = is_StopLiveVideo(m_hCamera, IS_WAIT);
452 m_bLiveStarted =
false;
455 is_ClearSequence(m_hCamera);
458 if (is_ExitCamera(m_hCamera) != IS_SUCCESS) {
470 is_DisableEvent(m_hCamera, m_event);
472 is_ExitEvent(m_hCamera, m_event);
473 CloseHandle(m_hEvent);
477 int enableEvent(
int event)
482 m_hEvent = CreateEvent(
nullptr, FALSE, FALSE,
nullptr);
483 if (m_hEvent ==
nullptr) {
486 ret = is_InitEvent(m_hCamera, m_hEvent, m_event);
488 ret = is_EnableEvent(m_hCamera, m_event);
496 if (is_WaitEvent(m_hCamera, m_event, EVENTTHREAD_WAIT_TIMEOUT) == IS_SUCCESS) {
498 if (WaitForSingleObject(m_hEvent, EVENTTHREAD_WAIT_TIMEOUT) == WAIT_OBJECT_0) {
509 m_pLastBuffer =
nullptr;
511 for (
unsigned int i = 0;
i <
sizeof(m_Images) /
sizeof(m_Images[0]);
i++) {
512 if (
nullptr != m_Images[i].pBuf) {
513 is_FreeImageMem(m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID);
516 m_Images[
i].pBuf =
nullptr;
517 m_Images[
i].nImageID = 0;
518 m_Images[
i].nImageSeqNum = 0;
522 std::string getActiveCameraModel()
const {
return m_CamListInfo.Model; }
524 std::string getActiveCameraSerialNumber()
const {
return m_CamListInfo.SerNo; }
526 int getBitsPerPixel(
int colormode)
531 case IS_CM_SENSOR_RAW8:
535 case IS_CM_SENSOR_RAW12:
536 case IS_CM_SENSOR_RAW16:
537 case IS_CM_BGR5_PACKED:
538 case IS_CM_BGR565_PACKED:
539 case IS_CM_UYVY_PACKED:
540 case IS_CM_CBYCRY_PACKED:
542 case IS_CM_RGB8_PACKED:
543 case IS_CM_BGR8_PACKED:
545 case IS_CM_RGBA8_PACKED:
546 case IS_CM_BGRA8_PACKED:
547 case IS_CM_RGBY8_PACKED:
548 case IS_CM_BGRY8_PACKED:
549 case IS_CM_RGB10_PACKED:
550 case IS_CM_BGR10_PACKED:
555 std::vector<unsigned int> getCameraIDList()
const
557 CameraList camera_list;
558 return camera_list.getCameraIDList();
561 std::vector<std::string> getCameraModelList()
const
563 CameraList camera_list;
564 return camera_list.getCameraModelList();
567 std::vector<std::string> getCameraSerialNumberList()
const
569 CameraList camera_list;
570 return camera_list.getCameraSerialNumberList();
573 unsigned int getFrameHeight()
const
575 if (!isConnected()) {
578 return static_cast<unsigned int>(m_BufferProps.height);
581 unsigned int getFrameWidth()
const
583 if (!isConnected()) {
586 return static_cast<unsigned int>(m_BufferProps.width);
589 double getFramerate()
const
597 if (is_GetFramesPerSecond(m_hCamera, &fps) != IS_SUCCESS) {
599 std::cout <<
"Unable to get acquisition frame rate" << std::endl;
605 INT getImageID(
char *pbuf)
610 for (
unsigned int i = 0;
i <
sizeof(m_Images) /
sizeof(m_Images[0]);
i++)
611 if (m_Images[i].pBuf == pbuf)
612 return m_Images[
i].nImageID;
617 INT getImageNum(
char *pbuf)
622 for (
unsigned int i = 0;
i <
sizeof(m_Images) /
sizeof(m_Images[0]);
i++)
623 if (m_Images[i].pBuf == pbuf)
624 return m_Images[
i].nImageSeqNum;
629 bool isConnected()
const {
return (m_hCamera != (HIDS)0); }
631 void loadParameters(
const std::string &filename)
638 int ret = is_ParameterSet(m_hCamera, IS_PARAMETERSET_CMD_LOAD_FILE, (
void *)filename_.c_str(), 0);
640 if (ret == IS_INVALID_CAMERA_TYPE) {
644 else if (ret == IS_INCOMPATIBLE_SETTING) {
646 "Because of incompatible settings, cannot load parameters from file %s",
filename.c_str()));
648 else if (ret != IS_SUCCESS) {
652 std::cout <<
"Parameters loaded sucessfully" << std::endl;
661 if (is_ExitCamera(m_hCamera) != IS_SUCCESS) {
667 m_hCamera = (HIDS)(m_CamListInfo.dwDeviceID | IS_USE_DEVICE_ID);
669 if (is_InitCamera(&m_hCamera, 0) != IS_SUCCESS) {
673 int ret = cameraInitialized();
674 if (ret != IS_SUCCESS) {
679 template <
class Type>
void open(vpImage<Type> &I)
682 I.
resize(m_SensorInfo.nMaxHeight, m_SensorInfo.nMaxWidth);
690 int searchDefImageFormats(
int suppportMask)
692 int ret = IS_SUCCESS;
695 IMAGE_FORMAT_LIST *pFormatList;
698 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_NUM_ENTRIES, (
void *)&nNumber,
sizeof(nNumber))) ==
700 (ret = is_AOI(m_hCamera, IS_AOI_IMAGE_GET_AOI, (
void *)&rectAOI,
sizeof(rectAOI))) == IS_SUCCESS) {
702 int nSize =
sizeof(IMAGE_FORMAT_LIST) + (nNumber - 1) *
sizeof(IMAGE_FORMAT_LIST);
703 pFormatList = (IMAGE_FORMAT_LIST *)(
new char[nSize]);
704 pFormatList->nNumListElements = nNumber;
705 pFormatList->nSizeOfListEntry =
sizeof(IMAGE_FORMAT_INFO);
707 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_LIST, (
void *)pFormatList, nSize)) == IS_SUCCESS) {
708 for (i = 0;
i < nNumber;
i++) {
709 if ((pFormatList->FormatInfo[i].nSupportedCaptureModes & suppportMask) &&
710 pFormatList->FormatInfo[i].nHeight == (UINT)rectAOI.s32Height &&
711 pFormatList->FormatInfo[i].nWidth == (UINT)rectAOI.s32Width) {
712 format = pFormatList->FormatInfo[
i].nFormatID;
721 delete (pFormatList);
729 int setActiveCamera(
unsigned int cam_index)
731 m_cameraList =
new CameraList;
732 m_activeCameraSelected = m_cameraList->setActiveCamera(cam_index);
733 if (!m_activeCameraSelected) {
734 m_CamListInfo = m_cameraList->getCameraInfo();
737 return m_activeCameraSelected;
740 std::string toUpper(
const std::basic_string<char> &s)
742 std::string s_upper =
s;
743 for (std::basic_string<char>::iterator p = s_upper.begin(); p != s_upper.end(); ++p) {
749 int setColorMode(
const std::string &color_mode)
751 if (!isConnected()) {
753 "Cannot set color mode. Connection to active uEye camera is not opened"));
756 std::string color_mode_upper = toUpper(color_mode);
757 int cm = IS_CM_MONO8;
758 if (color_mode_upper ==
"MONO8") {
761 else if (color_mode_upper ==
"RGB24") {
762 cm = IS_CM_BGR8_PACKED;
764 else if (color_mode_upper ==
"RGB32") {
765 cm = IS_CM_RGBA8_PACKED;
767 else if (color_mode_upper ==
"BAYER8") {
768 cm = IS_CM_SENSOR_RAW8;
774 INT ret = IS_SUCCESS;
775 if ((ret = is_SetColorMode(m_hCamera, cm)) != IS_SUCCESS) {
776 std::cout <<
"Could not set color mode of " << m_CamListInfo.Model <<
" to " << color_mode << std::endl;
784 int setFrameRate(
bool auto_frame_rate,
double frame_rate_hz)
786 if (!isConnected()) {
788 "Cannot set frame rate. Connection to active uEye camera is not opened"));
791 INT ret = IS_SUCCESS;
794 if (auto_frame_rate) {
795 double pval1 = 0, pval2 = 0;
798 bool autoShutterOn =
false;
799 is_SetAutoParameter(m_hCamera, IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2);
800 autoShutterOn |= (pval1 != 0);
801 is_SetAutoParameter(m_hCamera, IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2);
802 autoShutterOn |= (pval1 != 0);
803 if (!autoShutterOn) {
805 std::cout <<
"Auto shutter mode is not supported for " << m_CamListInfo.Model << std::endl;
807 return IS_NO_SUCCESS;
811 pval1 = auto_frame_rate;
812 if ((ret = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
813 if ((ret = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
815 std::cout <<
"Auto frame rate mode is not supported for " << m_CamListInfo.Model << std::endl;
817 return IS_NO_SUCCESS;
822 double minFrameTime, maxFrameTime, intervalFrameTime, newFrameRate;
824 if ((ret = is_GetFrameTimeRange(m_hCamera, &minFrameTime, &maxFrameTime, &intervalFrameTime)) != IS_SUCCESS) {
826 std::cout <<
"Failed to query valid frame rate range from " << m_CamListInfo.Model << std::endl;
830 CAP(frame_rate_hz, 1.0 / maxFrameTime, 1.0 / minFrameTime);
833 if ((ret = is_SetFrameRate(m_hCamera, frame_rate_hz, &newFrameRate)) != IS_SUCCESS) {
835 std::cout <<
"Failed to set frame rate to " << frame_rate_hz <<
" MHz for " << m_CamListInfo.Model
840 else if (frame_rate_hz != newFrameRate) {
841 frame_rate_hz = newFrameRate;
846 std::cout <<
"Updated frame rate for " << m_CamListInfo.Model <<
": "
847 << ((auto_frame_rate) ?
"auto" : std::to_string(frame_rate_hz)) <<
" Hz" << std::endl;
853 int setExposure(
bool auto_exposure,
double exposure_ms)
855 if (!isConnected()) {
860 INT err = IS_SUCCESS;
862 double minExposure, maxExposure;
866 double pval1 = auto_exposure, pval2 = 0;
867 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
868 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
869 std::cout <<
"Auto exposure mode is not supported for " << m_CamListInfo.Model << std::endl;
870 return IS_NO_SUCCESS;
877 if (((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MIN, (
void *)&minExposure,
878 sizeof(minExposure))) != IS_SUCCESS) ||
879 ((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MAX, (
void *)&maxExposure,
880 sizeof(maxExposure))) != IS_SUCCESS)) {
881 std::cout <<
"Failed to query valid exposure range from " << m_CamListInfo.Model << std::endl;
884 CAP(exposure_ms, minExposure, maxExposure);
887 if ((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_SET_EXPOSURE, (
void *)&(exposure_ms),
sizeof(exposure_ms))) !=
889 std::cout <<
"Failed to set exposure to " << exposure_ms <<
" ms for " << m_CamListInfo.Model << std::endl;
895 std::cout <<
"Updated exposure: " << ((auto_exposure) ?
"auto" : std::to_string(exposure_ms) +
" ms") <<
" for "
896 << m_CamListInfo.Model << std::endl;
902 int setGain(
bool auto_gain,
int master_gain,
bool gain_boost)
904 if (!isConnected()) {
905 throw(vpException(
vpException::fatalError,
"Cannot set gain. Connection to active uEye camera is not opened"));
908 INT err = IS_SUCCESS;
911 CAP(master_gain, 0, 100);
913 double pval1 = 0, pval2 = 0;
918 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
919 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
921 std::cout << m_CamListInfo.Model <<
" does not support auto gain mode" << std::endl;
923 return IS_NO_SUCCESS;
929 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
930 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
931 std::cout << m_CamListInfo.Model <<
" does not support auto gain mode" << std::endl;
936 if (is_SetGainBoost(m_hCamera, IS_GET_SUPPORTED_GAINBOOST) != IS_SET_GAINBOOST_ON) {
940 if ((err = is_SetGainBoost(m_hCamera, (gain_boost) ? IS_SET_GAINBOOST_ON : IS_SET_GAINBOOST_OFF)) !=
942 std::cout <<
"Failed to " << ((gain_boost) ?
"enable" :
"disable") <<
" gain boost for "
943 << m_CamListInfo.Model << std::endl;
948 if ((err = is_SetHardwareGain(m_hCamera, master_gain, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER,
949 IS_IGNORE_PARAMETER)) != IS_SUCCESS) {
950 std::cout <<
"Failed to set manual master gain: " << master_gain <<
" for " << m_CamListInfo.Model << std::endl;
951 return IS_NO_SUCCESS;
957 std::cout <<
"Updated gain for " << m_CamListInfo.Model <<
": auto" << std::endl;
960 std::cout <<
"Updated gain for " << m_CamListInfo.Model <<
": manual master gain " << master_gain << std::endl;
962 std::cout <<
"\n gain boost: " << (gain_boost ?
"enabled" :
"disabled") << std::endl;
969 void applySubsamplingSettings(
int subsamplingMode,
int nMode)
971 INT ret = IS_SUCCESS;
972 int currentSubsampling = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING);
973 if ((ret = is_SetSubSampling(m_hCamera, subsamplingMode | nMode)) != IS_SUCCESS) {
977 int newSubsampling = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING);
978 if ((nMode == IS_SUBSAMPLING_DISABLE) && (currentSubsampling == newSubsampling)) {
981 if ((ret = is_SetSubSampling(m_hCamera, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
987 void setSubsampling(
int factor)
989 if (!isConnected()) {
991 "Cannot set sub sampling factor. Connection to active uEye camera is not opened"));
994 INT hMode = IS_SUBSAMPLING_DISABLE, vMode = IS_SUBSAMPLING_DISABLE;
998 hMode = IS_SUBSAMPLING_2X_HORIZONTAL;
999 vMode = IS_SUBSAMPLING_2X_VERTICAL;
1002 hMode = IS_SUBSAMPLING_3X_HORIZONTAL;
1003 vMode = IS_SUBSAMPLING_3X_VERTICAL;
1006 hMode = IS_SUBSAMPLING_4X_HORIZONTAL;
1007 vMode = IS_SUBSAMPLING_4X_VERTICAL;
1010 hMode = IS_SUBSAMPLING_5X_HORIZONTAL;
1011 vMode = IS_SUBSAMPLING_5X_VERTICAL;
1014 hMode = IS_SUBSAMPLING_6X_HORIZONTAL;
1015 vMode = IS_SUBSAMPLING_6X_VERTICAL;
1018 hMode = IS_SUBSAMPLING_8X_HORIZONTAL;
1019 vMode = IS_SUBSAMPLING_8X_VERTICAL;
1022 hMode = IS_SUBSAMPLING_16X_HORIZONTAL;
1023 vMode = IS_SUBSAMPLING_16X_VERTICAL;
1026 hMode = IS_SUBSAMPLING_DISABLE;
1027 vMode = IS_SUBSAMPLING_DISABLE;
1030 if (m_bLive && m_bLiveStarted) {
1031 is_StopLiveVideo(m_hCamera, IS_WAIT);
1034 INT subsamplingModeH = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING) & IS_SUBSAMPLING_MASK_VERTICAL;
1035 applySubsamplingSettings(subsamplingModeH, hMode);
1037 INT subsamplingModeV = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING) & IS_SUBSAMPLING_MASK_HORIZONTAL;
1038 applySubsamplingSettings(subsamplingModeV, vMode);
1043 void setWhiteBalance(
bool auto_wb)
1045 if (!isConnected()) {
1047 "Cannot set white balance. Connection to active uEye camera is not opened"));
1050 double dblAutoWb = 0.0;
1054 is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb,
nullptr);
1057 is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb,
nullptr);
1061 is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb,
nullptr);
1062 is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb,
nullptr);
1070 ZeroMemory(&m_BufferProps,
sizeof(m_BufferProps));
1073 INT nRet = is_AOI(m_hCamera, IS_AOI_IMAGE_GET_AOI, (
void *)&rectAOI,
sizeof(rectAOI));
1075 if (nRet == IS_SUCCESS) {
1076 width = rectAOI.s32Width;
1077 height = rectAOI.s32Height;
1080 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
1082 if (colormode == IS_CM_BGR5_PACKED) {
1083 is_SetColorMode(m_hCamera, IS_CM_BGR565_PACKED);
1084 colormode = IS_CM_BGR565_PACKED;
1085 std::cout <<
"uEye color format 'IS_CM_BGR5_PACKED' actually not supported by vpUeyeGrabber, patched to "
1086 "'IS_CM_BGR565_PACKED'"
1091 ZeroMemory(&m_BufferProps,
sizeof(m_BufferProps));
1092 m_BufferProps.width =
width;
1093 m_BufferProps.height =
height;
1094 m_BufferProps.bitspp = getBitsPerPixel(colormode);
1100 std::cout <<
"Capture ready set up." << std::endl;
1106 void setVerbose(
bool verbose) { m_verbose = verbose; }
1110 int m_activeCameraSelected;
1111 SENSORINFO m_SensorInfo;
1113 UEYE_CAMERA_INFO m_CamListInfo;
1114 char *m_pLastBuffer;
1115 CameraList *m_cameraList;
1116 struct sBufferProps m_BufferProps;
1117 struct sCameraProps m_CameraProps;
1118 UEYE_IMAGE m_Images[IMAGE_COUNT];
1120 bool m_bLiveStarted;
1128 vpImage<vpRGBa> m_I_temp;
1171 m_impl->acquire(I, timestamp_camera, timestamp_system);
1196 m_impl->acquire(I, timestamp_camera, timestamp_system);
1240 return m_impl->getCameraSerialNumberList();
1300 return (m_impl->setActiveCamera(cam_index) ?
false :
true);
1320 return (m_impl->setColorMode(color_mode) ?
false :
true);
1338 return (m_impl->setExposure(auto_exposure, exposure_ms) ?
false :
true);
1373 return (m_impl->setFrameRate(auto_frame_rate, manual_frame_rate_hz) ?
false :
true);
1394 return (m_impl->setGain(auto_gain, master_gain, gain_boost) ?
false :
true);
1428#elif !defined(VISP_BUILD_SHARED_LIBS)
1430void dummy_vpUeyeGrabber() { }
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)
Definition of the vpImage class member functions.
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()