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) { \
77 bool bUsesImageFormats;
79 int nImgFmtDefaultNormal;
81 int nImgFmtDefaultTrigger;
87typedef struct _UEYE_IMAGE {
92} UEYE_IMAGE, *PUEYE_IMAGE;
94class vpUeyeGrabber::vpUeyeGrabberImpl
98 : m_hCamera((HIDS)0), m_activeCameraSelected(-1), m_pLastBuffer(NULL), m_cameraList(NULL), m_bLive(true),
99 m_bLiveStarted(false), m_verbose(false), m_I_temp()
101 ZeroMemory(&m_SensorInfo,
sizeof(SENSORINFO));
102 ZeroMemory(&m_CamInfo,
sizeof(CAMINFO));
103 ZeroMemory(&m_CamListInfo,
sizeof(UEYE_CAMERA_INFO));
104 ZeroMemory(m_Images,
sizeof(m_Images));
106 m_BufferProps.width = 0;
107 m_BufferProps.height = 0;
108 m_BufferProps.bitspp = 8;
116 m_activeCameraSelected = setActiveCamera(0);
119 ~vpUeyeGrabberImpl() { close(); }
123 INT ret = IS_SUCCESS;
131 ret = is_FreezeVideo(m_hCamera, IS_WAIT);
133 if (!m_bLiveStarted) {
134 ret = is_CaptureVideo(m_hCamera, IS_DONT_WAIT);
135 m_bLiveStarted =
true;
141 if (ret == IS_SUCCESS) {
143 char *pLast = NULL, *pMem = NULL;
145 is_GetActSeqBuf(m_hCamera, &dummy, &pMem, &pLast);
146 m_pLastBuffer = pLast;
148 if (!m_pLastBuffer || m_BufferProps.width < 1 || m_BufferProps.height < 1)
151 int nNum = getImageNum(m_pLastBuffer);
152 if (timestamp_camera != NULL || timestamp_system != NULL) {
153 int nImageID = getImageID(m_pLastBuffer);
154 UEYEIMAGEINFO ImageInfo;
155 if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo,
sizeof(ImageInfo)) == IS_SUCCESS) {
156 if (timestamp_camera != NULL) {
157 *timestamp_camera =
static_cast<double>(ImageInfo.u64TimestampDevice) / 10000.;
159 if (timestamp_system != NULL) {
160 std::stringstream ss;
161 ss << ImageInfo.TimestampSystem.wYear <<
":" << std::setfill(
'0') << std::setw(2)
162 << ImageInfo.TimestampSystem.wMonth <<
":" << std::setfill(
'0') << std::setw(2)
163 << ImageInfo.TimestampSystem.wDay <<
":" << std::setfill(
'0') << std::setw(2)
164 << ImageInfo.TimestampSystem.wHour <<
":" << std::setfill(
'0') << std::setw(2)
165 << ImageInfo.TimestampSystem.wMinute <<
":" << std::setfill(
'0') << std::setw(2)
166 << ImageInfo.TimestampSystem.wSecond <<
":" << std::setfill(
'0') << std::setw(3)
167 << ImageInfo.TimestampSystem.wMilliseconds;
168 *timestamp_system = ss.str();
173 helper::LockUnlockSeqBuffer lock(m_hCamera, nNum, m_pLastBuffer);
175 if (lock.OwnsLock()) {
177 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
182 memcpy(
reinterpret_cast<unsigned char *
>(I.
bitmap),
reinterpret_cast<unsigned char *
>(m_pLastBuffer),
183 m_BufferProps.width * m_BufferProps.height * m_BufferProps.bitspp / 8);
185 case IS_CM_SENSOR_RAW8:
186 m_I_temp.resize(m_BufferProps.height, m_BufferProps.width),
188 reinterpret_cast<unsigned char *
>(m_I_temp.bitmap),
189 m_BufferProps.width, m_BufferProps.height);
191 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
192 m_BufferProps.height);
194 case IS_CM_BGR565_PACKED:
197 case IS_CM_RGB8_PACKED:
199 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
200 m_BufferProps.height);
202 case IS_CM_BGR8_PACKED:
204 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
205 m_BufferProps.height);
207 case IS_CM_RGBA8_PACKED:
209 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
210 m_BufferProps.height);
212 case IS_CM_BGRA8_PACKED:
214 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
215 m_BufferProps.height);
223 void acquire(
vpImage<vpRGBa> &I,
double *timestamp_camera, std::string *timestamp_system)
225 INT ret = IS_SUCCESS;
233 ret = is_FreezeVideo(m_hCamera, IS_WAIT);
235 if (!m_bLiveStarted) {
237 ret = is_CaptureVideo(m_hCamera, IS_WAIT);
238 m_bLiveStarted =
true;
244 if (ret == IS_SUCCESS) {
246 char *pLast = NULL, *pMem = NULL;
248 is_GetActSeqBuf(m_hCamera, &dummy, &pMem, &pLast);
249 m_pLastBuffer = pLast;
251 if (!m_pLastBuffer || m_BufferProps.width < 1 || m_BufferProps.height < 1)
254 int nNum = getImageNum(m_pLastBuffer);
255 if (timestamp_camera != NULL || timestamp_system != NULL) {
256 int nImageID = getImageID(m_pLastBuffer);
257 UEYEIMAGEINFO ImageInfo;
258 if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo,
sizeof(ImageInfo)) == IS_SUCCESS) {
259 if (timestamp_camera != NULL) {
260 *timestamp_camera =
static_cast<double>(ImageInfo.u64TimestampDevice) / 10000.;
262 if (timestamp_system != NULL) {
263 std::stringstream ss;
264 ss << ImageInfo.TimestampSystem.wYear <<
":" << std::setfill(
'0') << std::setw(2)
265 << ImageInfo.TimestampSystem.wMonth <<
":" << std::setfill(
'0') << std::setw(2)
266 << ImageInfo.TimestampSystem.wDay <<
":" << std::setfill(
'0') << std::setw(2)
267 << ImageInfo.TimestampSystem.wHour <<
":" << std::setfill(
'0') << std::setw(2)
268 << ImageInfo.TimestampSystem.wMinute <<
":" << std::setfill(
'0') << std::setw(2)
269 << ImageInfo.TimestampSystem.wSecond <<
":" << std::setfill(
'0') << std::setw(3)
270 << ImageInfo.TimestampSystem.wMilliseconds;
271 *timestamp_system = ss.str();
276 helper::LockUnlockSeqBuffer lock(m_hCamera, nNum, m_pLastBuffer);
278 if (lock.OwnsLock()) {
280 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
286 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
287 m_BufferProps.height);
289 case IS_CM_SENSOR_RAW8:
291 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
292 m_BufferProps.height);
294 case IS_CM_BGR565_PACKED:
297 case IS_CM_RGB8_PACKED:
299 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
300 m_BufferProps.height);
302 case IS_CM_BGR8_PACKED:
304 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
305 m_BufferProps.height);
307 case IS_CM_RGBA8_PACKED:
308 memcpy(
reinterpret_cast<unsigned char *
>(I.
bitmap),
reinterpret_cast<unsigned char *
>(m_pLastBuffer),
309 m_BufferProps.width * m_BufferProps.height * m_BufferProps.bitspp / 8);
311 case IS_CM_BGRA8_PACKED:
313 reinterpret_cast<unsigned char *
>(I.
bitmap), m_BufferProps.width,
314 m_BufferProps.height);
324 m_pLastBuffer = NULL;
331 is_AOI(m_hCamera, IS_AOI_IMAGE_GET_POS_X_ABS, (
void *)&nAbsPosX,
sizeof(nAbsPosX));
332 is_AOI(m_hCamera, IS_AOI_IMAGE_GET_POS_Y_ABS, (
void *)&nAbsPosY,
sizeof(nAbsPosY));
334 is_ClearSequence(m_hCamera);
337 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++) {
338 nWidth = m_BufferProps.width;
339 nHeight = m_BufferProps.height;
342 m_BufferProps.width = nWidth = m_SensorInfo.nMaxWidth;
345 m_BufferProps.height = nHeight = m_SensorInfo.nMaxHeight;
348 if (is_AllocImageMem(m_hCamera, nWidth, nHeight, m_BufferProps.bitspp, &m_Images[i].pBuf,
349 &m_Images[i].nImageID) != IS_SUCCESS)
351 if (is_AddToSequence(m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID) != IS_SUCCESS)
354 m_Images[i].nImageSeqNum = i + 1;
355 m_Images[i].nBufferSize = nWidth * nHeight * m_BufferProps.bitspp / 8;
361 int cameraInitialized()
364 unsigned int uInitialParameterSet = IS_CONFIG_INITIAL_PARAMETERSET_NONE;
366 if ((ret = is_GetCameraInfo(m_hCamera, &m_CamInfo)) != IS_SUCCESS) {
368 }
else if ((ret = is_GetSensorInfo(m_hCamera, &m_SensorInfo)) != IS_SUCCESS) {
370 }
else if ((ret = is_Configuration(IS_CONFIG_INITIAL_PARAMETERSET_CMD_GET, &uInitialParameterSet,
371 sizeof(
unsigned int))) != IS_SUCCESS) {
380 if (uInitialParameterSet == IS_CONFIG_INITIAL_PARAMETERSET_NONE) {
381 ret = is_ResetToDefault(m_hCamera);
385 if (m_SensorInfo.nColorMode >= IS_COLORMODE_BAYER) {
386 colormode = IS_CM_BGRA8_PACKED;
388 colormode = IS_CM_MONO8;
391 if (is_SetColorMode(m_hCamera, colormode) != IS_SUCCESS) {
396 ZeroMemory(&m_CameraProps,
sizeof(m_CameraProps));
399 m_CameraProps.bUsesImageFormats =
false;
400 INT nAOISupported = 0;
401 if (is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_ARBITRARY_AOI_SUPPORTED, (
void *)&nAOISupported,
402 sizeof(nAOISupported)) == IS_SUCCESS) {
403 m_CameraProps.bUsesImageFormats = (nAOISupported == 0);
407 if (m_CameraProps.bUsesImageFormats) {
409 m_CameraProps.nImgFmtNormal = searchDefImageFormats(CAPTMODE_FREERUN | CAPTMODE_SINGLE);
410 m_CameraProps.nImgFmtDefaultNormal = m_CameraProps.nImgFmtNormal;
411 m_CameraProps.nImgFmtTrigger = searchDefImageFormats(CAPTMODE_TRIGGER_SOFT_SINGLE);
412 m_CameraProps.nImgFmtDefaultTrigger = m_CameraProps.nImgFmtTrigger;
414 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_SET_FORMAT, (
void *)&m_CameraProps.nImgFmtNormal,
415 sizeof(m_CameraProps.nImgFmtNormal))) == IS_SUCCESS) {
424 enableEvent(IS_SET_EVENT_FRAME);
427 m_pLastBuffer = NULL;
434 if (m_hCamera == IS_INVALID_HIDS)
438 if (m_bLive && m_bLiveStarted) {
442 nRet = is_StopLiveVideo(m_hCamera, IS_WAIT);
444 m_bLiveStarted =
false;
447 is_ClearSequence(m_hCamera);
450 if (is_ExitCamera(m_hCamera) != IS_SUCCESS) {
462 is_DisableEvent(m_hCamera, m_event);
464 is_ExitEvent(m_hCamera, m_event);
465 CloseHandle(m_hEvent);
469 int enableEvent(
int event)
474 m_hEvent = CreateEvent(NULL, FALSE, FALSE, NULL);
475 if (m_hEvent == NULL) {
478 ret = is_InitEvent(m_hCamera, m_hEvent, m_event);
480 ret = is_EnableEvent(m_hCamera, m_event);
488 if (is_WaitEvent(m_hCamera, m_event, EVENTTHREAD_WAIT_TIMEOUT) == IS_SUCCESS) {
490 if (WaitForSingleObject(m_hEvent, EVENTTHREAD_WAIT_TIMEOUT) == WAIT_OBJECT_0) {
500 m_pLastBuffer = NULL;
502 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++) {
503 if (NULL != m_Images[i].pBuf) {
504 is_FreeImageMem(m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID);
507 m_Images[i].pBuf = NULL;
508 m_Images[i].nImageID = 0;
509 m_Images[i].nImageSeqNum = 0;
513 std::string getActiveCameraModel()
const {
return m_CamListInfo.Model; }
515 std::string getActiveCameraSerialNumber()
const {
return m_CamListInfo.SerNo; }
517 int getBitsPerPixel(
int colormode)
522 case IS_CM_SENSOR_RAW8:
526 case IS_CM_SENSOR_RAW12:
527 case IS_CM_SENSOR_RAW16:
528 case IS_CM_BGR5_PACKED:
529 case IS_CM_BGR565_PACKED:
530 case IS_CM_UYVY_PACKED:
531 case IS_CM_CBYCRY_PACKED:
533 case IS_CM_RGB8_PACKED:
534 case IS_CM_BGR8_PACKED:
536 case IS_CM_RGBA8_PACKED:
537 case IS_CM_BGRA8_PACKED:
538 case IS_CM_RGBY8_PACKED:
539 case IS_CM_BGRY8_PACKED:
540 case IS_CM_RGB10_PACKED:
541 case IS_CM_BGR10_PACKED:
546 std::vector<unsigned int> getCameraIDList()
const
548 CameraList camera_list;
549 return camera_list.getCameraIDList();
552 std::vector<std::string> getCameraModelList()
const
554 CameraList camera_list;
555 return camera_list.getCameraModelList();
558 std::vector<std::string> getCameraSerialNumberList()
const
560 CameraList camera_list;
561 return camera_list.getCameraSerialNumberList();
564 unsigned int getFrameHeight()
const
566 if (!isConnected()) {
569 return static_cast<unsigned int>(m_BufferProps.height);
572 unsigned int getFrameWidth()
const
574 if (!isConnected()) {
577 return static_cast<unsigned int>(m_BufferProps.width);
580 double getFramerate()
const
588 if (is_GetFramesPerSecond(m_hCamera, &fps) != IS_SUCCESS) {
590 std::cout <<
"Unable to get acquisition frame rate" << std::endl;
596 INT getImageID(
char *pbuf)
601 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++)
602 if (m_Images[i].pBuf == pbuf)
603 return m_Images[i].nImageID;
608 INT getImageNum(
char *pbuf)
613 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++)
614 if (m_Images[i].pBuf == pbuf)
615 return m_Images[i].nImageSeqNum;
620 bool isConnected()
const {
return (m_hCamera != (HIDS)0); }
622 void loadParameters(
const std::string &filename)
628 const std::wstring filename_(filename.begin(), filename.end());
629 int ret = is_ParameterSet(m_hCamera, IS_PARAMETERSET_CMD_LOAD_FILE, (
void *)filename_.c_str(), 0);
631 if (ret == IS_INVALID_CAMERA_TYPE) {
634 }
else if (ret == IS_INCOMPATIBLE_SETTING) {
636 "Because of incompatible settings, cannot load parameters from file %s", filename.c_str()));
637 }
else if (ret != IS_SUCCESS) {
640 std::cout <<
"Parameters loaded sucessfully" << std::endl;
649 if (is_ExitCamera(m_hCamera) != IS_SUCCESS) {
655 m_hCamera = (HIDS)(m_CamListInfo.dwDeviceID | IS_USE_DEVICE_ID);
657 if (is_InitCamera(&m_hCamera, 0) != IS_SUCCESS) {
661 int ret = cameraInitialized();
662 if (ret != IS_SUCCESS) {
670 I.
resize(m_SensorInfo.nMaxHeight, m_SensorInfo.nMaxWidth);
678 int searchDefImageFormats(
int suppportMask)
680 int ret = IS_SUCCESS;
683 IMAGE_FORMAT_LIST *pFormatList;
686 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_NUM_ENTRIES, (
void *)&nNumber,
sizeof(nNumber))) ==
688 (ret = is_AOI(m_hCamera, IS_AOI_IMAGE_GET_AOI, (
void *)&rectAOI,
sizeof(rectAOI))) == IS_SUCCESS) {
690 int nSize =
sizeof(IMAGE_FORMAT_LIST) + (nNumber - 1) *
sizeof(IMAGE_FORMAT_LIST);
691 pFormatList = (IMAGE_FORMAT_LIST *)(
new char[nSize]);
692 pFormatList->nNumListElements = nNumber;
693 pFormatList->nSizeOfListEntry =
sizeof(IMAGE_FORMAT_INFO);
695 if ((ret = is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_LIST, (
void *)pFormatList, nSize)) == IS_SUCCESS) {
696 for (i = 0; i < nNumber; i++) {
697 if ((pFormatList->FormatInfo[i].nSupportedCaptureModes & suppportMask) &&
698 pFormatList->FormatInfo[i].nHeight == (UINT)rectAOI.s32Height &&
699 pFormatList->FormatInfo[i].nWidth == (UINT)rectAOI.s32Width) {
700 format = pFormatList->FormatInfo[i].nFormatID;
708 delete (pFormatList);
715 int setActiveCamera(
unsigned int cam_index)
717 m_cameraList =
new CameraList;
718 m_activeCameraSelected = m_cameraList->setActiveCamera(cam_index);
719 if (!m_activeCameraSelected) {
720 m_CamListInfo = m_cameraList->getCameraInfo();
723 return m_activeCameraSelected;
726 std::string toUpper(
const std::basic_string<char> &s)
728 std::string s_upper = s;
729 for (std::basic_string<char>::iterator p = s_upper.begin(); p != s_upper.end(); ++p) {
735 int setColorMode(
const std::string &color_mode)
737 if (!isConnected()) {
739 "Cannot set color mode. Connection to active uEye camera is not opened"));
742 std::string color_mode_upper = toUpper(color_mode);
743 int cm = IS_CM_MONO8;
744 if (color_mode_upper ==
"MONO8") {
746 }
else if (color_mode_upper ==
"RGB24") {
747 cm = IS_CM_BGR8_PACKED;
748 }
else if (color_mode_upper ==
"RGB32") {
749 cm = IS_CM_RGBA8_PACKED;
750 }
else if (color_mode_upper ==
"BAYER8") {
751 cm = IS_CM_SENSOR_RAW8;
756 INT ret = IS_SUCCESS;
757 if ((ret = is_SetColorMode(m_hCamera, cm)) != IS_SUCCESS) {
758 std::cout <<
"Could not set color mode of " << m_CamListInfo.Model <<
" to " << color_mode << std::endl;
765 int setFrameRate(
bool auto_frame_rate,
double frame_rate_hz)
767 if (!isConnected()) {
769 "Cannot set frame rate. Connection to active uEye camera is not opened"));
772 INT ret = IS_SUCCESS;
775 if (auto_frame_rate) {
776 double pval1 = 0, pval2 = 0;
779 bool autoShutterOn =
false;
780 is_SetAutoParameter(m_hCamera, IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2);
781 autoShutterOn |= (pval1 != 0);
782 is_SetAutoParameter(m_hCamera, IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2);
783 autoShutterOn |= (pval1 != 0);
784 if (!autoShutterOn) {
786 std::cout <<
"Auto shutter mode is not supported for " << m_CamListInfo.Model << std::endl;
788 return IS_NO_SUCCESS;
792 pval1 = auto_frame_rate;
793 if ((ret = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
794 if ((ret = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
796 std::cout <<
"Auto frame rate mode is not supported for " << m_CamListInfo.Model << std::endl;
798 return IS_NO_SUCCESS;
802 double minFrameTime, maxFrameTime, intervalFrameTime, newFrameRate;
804 if ((ret = is_GetFrameTimeRange(m_hCamera, &minFrameTime, &maxFrameTime, &intervalFrameTime)) != IS_SUCCESS) {
806 std::cout <<
"Failed to query valid frame rate range from " << m_CamListInfo.Model << std::endl;
810 CAP(frame_rate_hz, 1.0 / maxFrameTime, 1.0 / minFrameTime);
813 if ((ret = is_SetFrameRate(m_hCamera, frame_rate_hz, &newFrameRate)) != IS_SUCCESS) {
815 std::cout <<
"Failed to set frame rate to " << frame_rate_hz <<
" MHz for " << m_CamListInfo.Model
819 }
else if (frame_rate_hz != newFrameRate) {
820 frame_rate_hz = newFrameRate;
825 std::cout <<
"Updated frame rate for " << m_CamListInfo.Model <<
": "
826 << ((auto_frame_rate) ?
"auto" : std::to_string(frame_rate_hz)) <<
" Hz" << std::endl;
832 int setExposure(
bool auto_exposure,
double exposure_ms)
834 if (!isConnected()) {
839 INT err = IS_SUCCESS;
841 double minExposure, maxExposure;
845 double pval1 = auto_exposure, pval2 = 0;
846 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
847 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
848 std::cout <<
"Auto exposure mode is not supported for " << m_CamListInfo.Model << std::endl;
849 return IS_NO_SUCCESS;
856 if (((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MIN, (
void *)&minExposure,
857 sizeof(minExposure))) != IS_SUCCESS) ||
858 ((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MAX, (
void *)&maxExposure,
859 sizeof(maxExposure))) != IS_SUCCESS)) {
860 std::cout <<
"Failed to query valid exposure range from " << m_CamListInfo.Model << std::endl;
863 CAP(exposure_ms, minExposure, maxExposure);
866 if ((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_SET_EXPOSURE, (
void *)&(exposure_ms),
sizeof(exposure_ms))) !=
868 std::cout <<
"Failed to set exposure to " << exposure_ms <<
" ms for " << m_CamListInfo.Model << std::endl;
874 std::cout <<
"Updated exposure: " << ((auto_exposure) ?
"auto" : std::to_string(exposure_ms) +
" ms") <<
" for "
875 << m_CamListInfo.Model << std::endl;
881 int setGain(
bool auto_gain,
int master_gain,
bool gain_boost)
883 if (!isConnected()) {
887 INT err = IS_SUCCESS;
890 CAP(master_gain, 0, 100);
892 double pval1 = 0, pval2 = 0;
897 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
898 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
900 std::cout << m_CamListInfo.Model <<
" does not support auto gain mode" << std::endl;
902 return IS_NO_SUCCESS;
907 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
908 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
909 std::cout << m_CamListInfo.Model <<
" does not support auto gain mode" << std::endl;
914 if (is_SetGainBoost(m_hCamera, IS_GET_SUPPORTED_GAINBOOST) != IS_SET_GAINBOOST_ON) {
917 if ((err = is_SetGainBoost(m_hCamera, (gain_boost) ? IS_SET_GAINBOOST_ON : IS_SET_GAINBOOST_OFF)) !=
919 std::cout <<
"Failed to " << ((gain_boost) ?
"enable" :
"disable") <<
" gain boost for "
920 << m_CamListInfo.Model << std::endl;
925 if ((err = is_SetHardwareGain(m_hCamera, master_gain, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER,
926 IS_IGNORE_PARAMETER)) != IS_SUCCESS) {
927 std::cout <<
"Failed to set manual master gain: " << master_gain <<
" for " << m_CamListInfo.Model << std::endl;
928 return IS_NO_SUCCESS;
934 std::cout <<
"Updated gain for " << m_CamListInfo.Model <<
": auto" << std::endl;
936 std::cout <<
"Updated gain for " << m_CamListInfo.Model <<
": manual master gain " << master_gain << std::endl;
938 std::cout <<
"\n gain boost: " << (gain_boost ?
"enabled" :
"disabled") << std::endl;
945 void applySubsamplingSettings(
int subsamplingMode,
int nMode)
947 INT ret = IS_SUCCESS;
948 int currentSubsampling = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING);
949 if ((ret = is_SetSubSampling(m_hCamera, subsamplingMode | nMode)) != IS_SUCCESS) {
953 int newSubsampling = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING);
954 if ((nMode == IS_SUBSAMPLING_DISABLE) && (currentSubsampling == newSubsampling)) {
957 if ((ret = is_SetSubSampling(m_hCamera, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
963 void setSubsampling(
int factor)
965 if (!isConnected()) {
967 "Cannot set sub sampling factor. Connection to active uEye camera is not opened"));
970 INT hMode = IS_SUBSAMPLING_DISABLE, vMode = IS_SUBSAMPLING_DISABLE;
974 hMode = IS_SUBSAMPLING_2X_HORIZONTAL;
975 vMode = IS_SUBSAMPLING_2X_VERTICAL;
978 hMode = IS_SUBSAMPLING_3X_HORIZONTAL;
979 vMode = IS_SUBSAMPLING_3X_VERTICAL;
982 hMode = IS_SUBSAMPLING_4X_HORIZONTAL;
983 vMode = IS_SUBSAMPLING_4X_VERTICAL;
986 hMode = IS_SUBSAMPLING_5X_HORIZONTAL;
987 vMode = IS_SUBSAMPLING_5X_VERTICAL;
990 hMode = IS_SUBSAMPLING_6X_HORIZONTAL;
991 vMode = IS_SUBSAMPLING_6X_VERTICAL;
994 hMode = IS_SUBSAMPLING_8X_HORIZONTAL;
995 vMode = IS_SUBSAMPLING_8X_VERTICAL;
998 hMode = IS_SUBSAMPLING_16X_HORIZONTAL;
999 vMode = IS_SUBSAMPLING_16X_VERTICAL;
1002 hMode = IS_SUBSAMPLING_DISABLE;
1003 vMode = IS_SUBSAMPLING_DISABLE;
1006 if (m_bLive && m_bLiveStarted) {
1007 is_StopLiveVideo(m_hCamera, IS_WAIT);
1010 INT subsamplingModeH = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING) & IS_SUBSAMPLING_MASK_VERTICAL;
1011 applySubsamplingSettings(subsamplingModeH, hMode);
1013 INT subsamplingModeV = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING) & IS_SUBSAMPLING_MASK_HORIZONTAL;
1014 applySubsamplingSettings(subsamplingModeV, vMode);
1019 void setWhiteBalance(
bool auto_wb)
1021 if (!isConnected()) {
1023 "Cannot set white balance. Connection to active uEye camera is not opened"));
1026 double dblAutoWb = 0.0;
1030 is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb, NULL);
1033 is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb, NULL);
1036 is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb, NULL);
1037 is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb, NULL);
1045 ZeroMemory(&m_BufferProps,
sizeof(m_BufferProps));
1048 INT nRet = is_AOI(m_hCamera, IS_AOI_IMAGE_GET_AOI, (
void *)&rectAOI,
sizeof(rectAOI));
1050 if (nRet == IS_SUCCESS) {
1051 width = rectAOI.s32Width;
1052 height = rectAOI.s32Height;
1055 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
1057 if (colormode == IS_CM_BGR5_PACKED) {
1058 is_SetColorMode(m_hCamera, IS_CM_BGR565_PACKED);
1059 colormode = IS_CM_BGR565_PACKED;
1060 std::cout <<
"uEye color format 'IS_CM_BGR5_PACKED' actually not supported by vpUeyeGrabber, patched to "
1061 "'IS_CM_BGR565_PACKED'"
1066 ZeroMemory(&m_BufferProps,
sizeof(m_BufferProps));
1067 m_BufferProps.width = width;
1068 m_BufferProps.height = height;
1069 m_BufferProps.bitspp = getBitsPerPixel(colormode);
1075 std::cout <<
"Capture ready set up." << std::endl;
1081 void setVerbose(
bool verbose) { m_verbose = verbose; }
1085 int m_activeCameraSelected;
1086 SENSORINFO m_SensorInfo;
1088 UEYE_CAMERA_INFO m_CamListInfo;
1089 char *m_pLastBuffer;
1090 CameraList *m_cameraList;
1091 struct sBufferProps m_BufferProps;
1092 struct sCameraProps m_CameraProps;
1093 UEYE_IMAGE m_Images[IMAGE_COUNT];
1095 bool m_bLiveStarted;
1146 m_impl->acquire(I, timestamp_camera, timestamp_system);
1171 m_impl->acquire(I, timestamp_camera, timestamp_system);
1215 return m_impl->getCameraSerialNumberList();
1275 return (m_impl->setActiveCamera(cam_index) ?
false :
true);
1295 return (m_impl->setColorMode(color_mode) ?
false :
true);
1313 return (m_impl->setExposure(auto_exposure, exposure_ms) ?
false :
true);
1348 return (m_impl->setFrameRate(auto_frame_rate, manual_frame_rate_hz) ?
false :
true);
1369 return (m_impl->setGain(auto_gain, master_gain, gain_boost) ?
false :
true);
1403#elif !defined(VISP_BUILD_SHARED_LIBS)
1405void 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)
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
void acquire(vpImage< unsigned char > &I, double *timestamp_camera=NULL, std::string *timestamp_system=NULL)
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)
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()