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_nMemoryId(0), m_nColorMode(0), m_nBitsPerPixel(0), m_activeCameraSelected(-1),
102 m_pLastBuffer(NULL), m_cameraList(NULL), m_bLive(true), 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;
119 m_activeCameraSelected = setActiveCamera(0);
129 INT ret = IS_SUCCESS;
137 ret = is_FreezeVideo(m_hCamera, IS_WAIT);
140 if (! m_bLiveStarted) {
141 ret = is_CaptureVideo(m_hCamera, IS_DONT_WAIT);
142 m_bLiveStarted =
true;
148 if (ret == IS_SUCCESS) {
150 char *pLast = NULL, *pMem = NULL;
152 is_GetActSeqBuf (m_hCamera, &dummy, &pMem, &pLast);
153 m_pLastBuffer = pLast;
155 if (!m_pLastBuffer || m_BufferProps.width < 1 || m_BufferProps.height < 1)
158 int nNum = getImageNum (m_pLastBuffer);
159 if (timestamp_camera != NULL || timestamp_system != NULL) {
160 int nImageID = getImageID(m_pLastBuffer);
161 UEYEIMAGEINFO ImageInfo;
162 if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo,
sizeof (ImageInfo)) == IS_SUCCESS) {
163 if (timestamp_camera != NULL) {
164 *timestamp_camera =
static_cast<double>(ImageInfo.u64TimestampDevice) / 10000.;
166 if (timestamp_system != NULL) {
167 std::stringstream ss;
168 ss << ImageInfo.TimestampSystem.wYear <<
":" 169 << std::setfill(
'0') << std::setw(2) << ImageInfo.TimestampSystem.wMonth <<
":" 170 << std::setfill(
'0') << std::setw(2) << ImageInfo.TimestampSystem.wDay <<
":" 171 << std::setfill(
'0') << std::setw(2) << ImageInfo.TimestampSystem.wHour <<
":" 172 << std::setfill(
'0') << std::setw(2) << ImageInfo.TimestampSystem.wMinute <<
":" 173 << std::setfill(
'0') << std::setw(2) << ImageInfo.TimestampSystem.wSecond <<
":" 174 << std::setfill(
'0') << std::setw(3) << ImageInfo.TimestampSystem.wMilliseconds;
175 *timestamp_system = ss.str();
180 helper::LockUnlockSeqBuffer lock(m_hCamera, nNum, m_pLastBuffer);
182 if (lock.OwnsLock()) {
184 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
189 memcpy(reinterpret_cast<unsigned char*>(I.
bitmap), reinterpret_cast<unsigned char*>(m_pLastBuffer), m_BufferProps.width * m_BufferProps.height * m_BufferProps.bitspp / 8);
191 case IS_CM_SENSOR_RAW8:
192 m_I_temp.resize( m_BufferProps.height, m_BufferProps.width ),
194 reinterpret_cast< unsigned char * >( m_I_temp.bitmap ),
195 m_BufferProps.width, m_BufferProps.height );
197 reinterpret_cast< unsigned char * >( I.
bitmap ), m_BufferProps.width,
198 m_BufferProps.height );
200 case IS_CM_BGR565_PACKED:
203 case IS_CM_RGB8_PACKED:
205 m_BufferProps.width, m_BufferProps.height);
207 case IS_CM_BGR8_PACKED:
209 m_BufferProps.width, m_BufferProps.height);
211 case IS_CM_RGBA8_PACKED:
213 m_BufferProps.width, m_BufferProps.height);
215 case IS_CM_BGRA8_PACKED:
217 m_BufferProps.width, m_BufferProps.height);
225 void acquire(
vpImage<vpRGBa> &I,
double *timestamp_camera, std::string *timestamp_system)
227 INT ret = IS_SUCCESS;
235 ret = is_FreezeVideo(m_hCamera, IS_WAIT);
238 if (! m_bLiveStarted) {
240 ret = is_CaptureVideo(m_hCamera, IS_WAIT);
241 m_bLiveStarted =
true;
247 if (ret == IS_SUCCESS) {
249 char *pLast = NULL, *pMem = NULL;
251 is_GetActSeqBuf (m_hCamera, &dummy, &pMem, &pLast);
252 m_pLastBuffer = pLast;
254 if (!m_pLastBuffer || m_BufferProps.width < 1 || m_BufferProps.height < 1)
257 int nNum = getImageNum (m_pLastBuffer);
258 if (timestamp_camera != NULL || timestamp_system != NULL) {
259 int nImageID = getImageID(m_pLastBuffer);
260 UEYEIMAGEINFO ImageInfo;
261 if (is_GetImageInfo(m_hCamera, nImageID, &ImageInfo,
sizeof (ImageInfo)) == IS_SUCCESS) {
262 if (timestamp_camera != NULL) {
263 *timestamp_camera =
static_cast<double>(ImageInfo.u64TimestampDevice) / 10000.;
265 if (timestamp_system != NULL) {
266 std::stringstream ss;
267 ss << ImageInfo.TimestampSystem.wYear <<
":" 268 << std::setfill(
'0') << std::setw(2) << ImageInfo.TimestampSystem.wMonth <<
":" 269 << std::setfill(
'0') << std::setw(2) << ImageInfo.TimestampSystem.wDay <<
":" 270 << std::setfill(
'0') << std::setw(2) << ImageInfo.TimestampSystem.wHour <<
":" 271 << std::setfill(
'0') << std::setw(2) << ImageInfo.TimestampSystem.wMinute <<
":" 272 << std::setfill(
'0') << std::setw(2) << ImageInfo.TimestampSystem.wSecond <<
":" 273 << std::setfill(
'0') << std::setw(3) << ImageInfo.TimestampSystem.wMilliseconds;
274 *timestamp_system = ss.str();
279 helper::LockUnlockSeqBuffer lock(m_hCamera, nNum, m_pLastBuffer);
281 if (lock.OwnsLock()) {
283 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
289 m_BufferProps.width, m_BufferProps.height);
291 case IS_CM_SENSOR_RAW8:
293 reinterpret_cast< unsigned char * >( I.
bitmap ),
294 m_BufferProps.width, m_BufferProps.height );
296 case IS_CM_BGR565_PACKED:
299 case IS_CM_RGB8_PACKED:
301 m_BufferProps.width, m_BufferProps.height);
303 case IS_CM_BGR8_PACKED:
305 m_BufferProps.width, m_BufferProps.height);
307 case IS_CM_RGBA8_PACKED:
308 memcpy(reinterpret_cast<unsigned char*>(I.
bitmap), reinterpret_cast<unsigned char*>(m_pLastBuffer), m_BufferProps.width * m_BufferProps.height * m_BufferProps.bitspp / 8);
310 case IS_CM_BGRA8_PACKED:
312 m_BufferProps.width, m_BufferProps.height);
322 m_pLastBuffer = NULL;
329 is_AOI(m_hCamera, IS_AOI_IMAGE_GET_POS_X_ABS, (
void*)&nAbsPosX ,
sizeof(nAbsPosX));
330 is_AOI(m_hCamera, IS_AOI_IMAGE_GET_POS_Y_ABS, (
void*)&nAbsPosY ,
sizeof(nAbsPosY));
332 is_ClearSequence(m_hCamera);
335 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++) {
336 nWidth = m_BufferProps.width;
337 nHeight = m_BufferProps.height;
340 m_BufferProps.width = nWidth = m_SensorInfo.nMaxWidth;
343 m_BufferProps.height = nHeight = m_SensorInfo.nMaxHeight;
346 if (is_AllocImageMem (m_hCamera, nWidth, nHeight, m_BufferProps.bitspp, &m_Images[i].pBuf,
347 &m_Images[i].nImageID) != IS_SUCCESS)
349 if (is_AddToSequence (m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID) != IS_SUCCESS)
352 m_Images[i].nImageSeqNum = i + 1;
353 m_Images[i].nBufferSize = nWidth * nHeight * m_BufferProps.bitspp / 8;
359 int cameraInitialized()
362 unsigned int uInitialParameterSet = IS_CONFIG_INITIAL_PARAMETERSET_NONE;
364 if ((ret=is_GetCameraInfo (m_hCamera, &m_CamInfo)) != IS_SUCCESS) {
367 else if ((ret=is_GetSensorInfo (m_hCamera, &m_SensorInfo)) != IS_SUCCESS) {
370 else if ((ret = is_Configuration(IS_CONFIG_INITIAL_PARAMETERSET_CMD_GET, &uInitialParameterSet,
sizeof(
unsigned int))) != IS_SUCCESS) {
381 if (uInitialParameterSet == IS_CONFIG_INITIAL_PARAMETERSET_NONE)
383 ret = is_ResetToDefault (m_hCamera);
387 if (m_SensorInfo.nColorMode >= IS_COLORMODE_BAYER) {
388 colormode = IS_CM_BGRA8_PACKED;
391 colormode = IS_CM_MONO8;
394 if (is_SetColorMode (m_hCamera, colormode) != IS_SUCCESS) {
399 ZeroMemory (&m_CameraProps,
sizeof(m_CameraProps));
402 m_CameraProps.bUsesImageFormats =
false;
403 INT nAOISupported = 0;
404 if (is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_ARBITRARY_AOI_SUPPORTED, (
void*)&nAOISupported,
405 sizeof(nAOISupported)) == IS_SUCCESS) {
406 m_CameraProps.bUsesImageFormats = (nAOISupported == 0);
410 if (m_CameraProps.bUsesImageFormats) {
412 m_CameraProps.nImgFmtNormal = searchDefImageFormats(CAPTMODE_FREERUN | CAPTMODE_SINGLE);
413 m_CameraProps.nImgFmtDefaultNormal = m_CameraProps.nImgFmtNormal;
414 m_CameraProps.nImgFmtTrigger = searchDefImageFormats(CAPTMODE_TRIGGER_SOFT_SINGLE);
415 m_CameraProps.nImgFmtDefaultTrigger = m_CameraProps.nImgFmtTrigger;
417 if ((ret=is_ImageFormat(m_hCamera, IMGFRMT_CMD_SET_FORMAT, (
void*)&m_CameraProps.nImgFmtNormal,
418 sizeof(m_CameraProps.nImgFmtNormal))) == IS_SUCCESS) {
427 enableEvent(IS_SET_EVENT_FRAME);
430 m_pLastBuffer = NULL;
437 if (m_hCamera == IS_INVALID_HIDS)
441 if (m_bLive && m_bLiveStarted) {
445 nRet = is_StopLiveVideo(m_hCamera, IS_WAIT);
447 m_bLiveStarted =
false;
450 is_ClearSequence(m_hCamera);
453 if (is_ExitCamera(m_hCamera) != IS_SUCCESS) {
465 is_DisableEvent (m_hCamera, m_event);
467 is_ExitEvent(m_hCamera, m_event);
468 CloseHandle(m_hEvent);
473 int enableEvent(
int event)
478 m_hEvent = CreateEvent(NULL, FALSE, FALSE, NULL);
479 if (m_hEvent == NULL) {
482 ret = is_InitEvent(m_hCamera, m_hEvent, m_event);
484 ret = is_EnableEvent (m_hCamera, m_event);
492 if (is_WaitEvent (m_hCamera, m_event, EVENTTHREAD_WAIT_TIMEOUT) == IS_SUCCESS) {
494 if (WaitForSingleObject(m_hEvent, EVENTTHREAD_WAIT_TIMEOUT) == WAIT_OBJECT_0) {
505 m_pLastBuffer = NULL;
507 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++) {
508 if (NULL != m_Images[i].pBuf) {
509 is_FreeImageMem (m_hCamera, m_Images[i].pBuf, m_Images[i].nImageID);
512 m_Images[i].pBuf = NULL;
513 m_Images[i].nImageID = 0;
514 m_Images[i].nImageSeqNum = 0;
518 std::string getActiveCameraModel()
const 520 return m_CamListInfo.Model;
523 std::string getActiveCameraSerialNumber()
const 525 return m_CamListInfo.SerNo;
528 int getBitsPerPixel(
int colormode)
534 case IS_CM_SENSOR_RAW8:
538 case IS_CM_SENSOR_RAW12:
539 case IS_CM_SENSOR_RAW16:
540 case IS_CM_BGR5_PACKED:
541 case IS_CM_BGR565_PACKED:
542 case IS_CM_UYVY_PACKED:
543 case IS_CM_CBYCRY_PACKED:
545 case IS_CM_RGB8_PACKED:
546 case IS_CM_BGR8_PACKED:
548 case IS_CM_RGBA8_PACKED:
549 case IS_CM_BGRA8_PACKED:
550 case IS_CM_RGBY8_PACKED:
551 case IS_CM_BGRY8_PACKED:
552 case IS_CM_RGB10_PACKED:
553 case IS_CM_BGR10_PACKED:
558 std::vector<unsigned int> getCameraIDList()
const 560 CameraList camera_list;
561 return camera_list.getCameraIDList();
564 std::vector<std::string> getCameraModelList()
const 566 CameraList camera_list;
567 return camera_list.getCameraModelList();
570 std::vector<std::string> getCameraSerialNumberList()
const 572 CameraList camera_list;
573 return camera_list.getCameraSerialNumberList();
576 unsigned int getFrameHeight()
const 578 if (!isConnected()) {
581 return static_cast<unsigned int>(m_BufferProps.height);
584 unsigned int getFrameWidth()
const 586 if (!isConnected()) {
589 return static_cast<unsigned int>(m_BufferProps.width);
592 double getFramerate()
const 600 if (is_GetFramesPerSecond (m_hCamera, &fps) != IS_SUCCESS) {
602 std::cout <<
"Unable to get acquisition frame rate" << std::endl;
608 INT getImageID (
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].nImageID;
620 INT getImageNum(
char* pbuf)
625 for (
unsigned int i = 0; i <
sizeof(m_Images) /
sizeof(m_Images[0]); i++)
626 if (m_Images[i].pBuf == pbuf)
627 return m_Images[i].nImageSeqNum;
632 bool isConnected()
const 634 return (m_hCamera != (HIDS) 0);
637 void loadParameters(
const std::string &filename)
643 const std::wstring filename_(filename.begin(), filename.end());
644 int ret = is_ParameterSet(m_hCamera, IS_PARAMETERSET_CMD_LOAD_FILE, (
void*) filename_.c_str(), 0);
646 if (ret == IS_INVALID_CAMERA_TYPE) {
649 else if (ret == IS_INCOMPATIBLE_SETTING) {
652 else if (ret != IS_SUCCESS) {
656 std::cout <<
"Parameters loaded sucessfully" << std::endl;
665 if (is_ExitCamera(m_hCamera) != IS_SUCCESS) {
671 m_hCamera = (HIDS) (m_CamListInfo.dwDeviceID | IS_USE_DEVICE_ID);
673 if (is_InitCamera(&m_hCamera, 0) != IS_SUCCESS) {
677 int ret = cameraInitialized();
678 if (ret != IS_SUCCESS) {
683 template <
class Type>
687 I.
resize(m_SensorInfo.nMaxHeight, m_SensorInfo.nMaxWidth);
695 int searchDefImageFormats(
int suppportMask)
697 int ret = IS_SUCCESS;
700 IMAGE_FORMAT_LIST *pFormatList;
703 if ((ret=is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_NUM_ENTRIES, (
void*)&nNumber,
sizeof(nNumber))) == IS_SUCCESS &&
704 (ret=is_AOI(m_hCamera, IS_AOI_IMAGE_GET_AOI, (
void*)&rectAOI,
sizeof(rectAOI))) == IS_SUCCESS) {
706 int nSize =
sizeof(IMAGE_FORMAT_LIST) + (nNumber - 1) *
sizeof(IMAGE_FORMAT_LIST);
707 pFormatList = (IMAGE_FORMAT_LIST*)(
new char[nSize]);
708 pFormatList->nNumListElements = nNumber;
709 pFormatList->nSizeOfListEntry =
sizeof(IMAGE_FORMAT_INFO);
711 if((ret=is_ImageFormat(m_hCamera, IMGFRMT_CMD_GET_LIST, (
void*)pFormatList, nSize)) == IS_SUCCESS) {
712 for(i=0; i<nNumber; i++) {
713 if ((pFormatList->FormatInfo[i].nSupportedCaptureModes & suppportMask) &&
714 pFormatList->FormatInfo[i].nHeight == (UINT)rectAOI.s32Height &&
715 pFormatList->FormatInfo[i].nWidth == (UINT)rectAOI.s32Width) {
716 format = pFormatList->FormatInfo[i].nFormatID;
725 delete (pFormatList);
734 int setActiveCamera(
unsigned int cam_index)
736 m_cameraList =
new CameraList;
737 m_activeCameraSelected = m_cameraList->setActiveCamera(cam_index);
738 if (! m_activeCameraSelected) {
739 m_CamListInfo = m_cameraList->getCameraInfo();
742 return m_activeCameraSelected;
745 std::string toUpper(
const std::basic_string<char>& s)
747 std::string s_upper = s;
748 for (std::basic_string<char>::iterator p = s_upper.begin(); p != s_upper.end(); ++p) {
754 int setColorMode(
const std::string &color_mode)
756 if (! isConnected()) {
760 std::string color_mode_upper = toUpper(color_mode);
761 int cm = IS_CM_MONO8;
762 if (color_mode_upper ==
"MONO8") {
765 else if (color_mode_upper ==
"RGB24") {
766 cm = IS_CM_BGR8_PACKED;
768 else if (color_mode_upper ==
"RGB32") {
769 cm = IS_CM_RGBA8_PACKED;
771 else if ( color_mode_upper ==
"BAYER8" ) {
772 cm = IS_CM_SENSOR_RAW8;
778 INT ret = IS_SUCCESS;
779 if ((ret = is_SetColorMode(m_hCamera, cm)) != IS_SUCCESS) {
780 std::cout <<
"Could not set color mode of " << m_CamListInfo.Model <<
" to " << color_mode << std::endl;
788 int setFrameRate(
bool auto_frame_rate,
double frame_rate_hz)
790 if (! isConnected()) {
794 INT ret = IS_SUCCESS;
797 if (auto_frame_rate) {
798 double pval1 = 0, pval2 = 0;
801 bool autoShutterOn =
false;
802 is_SetAutoParameter(m_hCamera, IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2);
803 autoShutterOn |= (pval1 != 0);
804 is_SetAutoParameter(m_hCamera, IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2);
805 autoShutterOn |= (pval1 != 0);
806 if (!autoShutterOn) {
808 std::cout <<
"Auto shutter mode is not supported for " << m_CamListInfo.Model << std::endl;
810 return IS_NO_SUCCESS;
814 pval1 = auto_frame_rate;
815 if ((ret = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_FRAMERATE,
816 &pval1, &pval2)) != IS_SUCCESS) {
817 if ((ret = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_FRAMERATE,
818 &pval1, &pval2)) != IS_SUCCESS) {
820 std::cout <<
"Auto frame rate mode is not supported for " << m_CamListInfo.Model << std::endl;
822 return IS_NO_SUCCESS;
827 double minFrameTime, maxFrameTime, intervalFrameTime, newFrameRate;
829 if ((ret = is_GetFrameTimeRange(m_hCamera, &minFrameTime,
830 &maxFrameTime, &intervalFrameTime)) != IS_SUCCESS) {
832 std::cout <<
"Failed to query valid frame rate range from " << m_CamListInfo.Model << std::endl;
836 CAP(frame_rate_hz, 1.0/maxFrameTime, 1.0/minFrameTime);
839 if ((ret = is_SetFrameRate(m_hCamera, frame_rate_hz, &newFrameRate)) != IS_SUCCESS) {
841 std::cout <<
"Failed to set frame rate to " << frame_rate_hz <<
842 " MHz for " << m_CamListInfo.Model << std::endl;
845 }
else if (frame_rate_hz != newFrameRate) {
846 frame_rate_hz = newFrameRate;
851 std::cout <<
"Updated frame rate for " << m_CamListInfo.Model <<
": " <<
852 ((auto_frame_rate) ?
"auto" : std::to_string(frame_rate_hz)) <<
" Hz" << std::endl;
858 int setExposure(
bool auto_exposure,
double exposure_ms)
860 if (! isConnected()) {
864 INT err = IS_SUCCESS;
866 double minExposure, maxExposure;
870 double pval1 = auto_exposure, pval2 = 0;
871 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_SHUTTER,
872 &pval1, &pval2)) != IS_SUCCESS) {
873 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SHUTTER,
874 &pval1, &pval2)) != IS_SUCCESS) {
875 std::cout <<
"Auto exposure mode is not supported for " << m_CamListInfo.Model << std::endl;
876 return IS_NO_SUCCESS;
883 if (((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MIN,
884 (
void*) &minExposure,
sizeof(minExposure))) != IS_SUCCESS) ||
885 ((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MAX,
886 (
void*) &maxExposure,
sizeof(maxExposure))) != IS_SUCCESS)) {
887 std::cout <<
"Failed to query valid exposure range from " << m_CamListInfo.Model << std::endl;
890 CAP(exposure_ms, minExposure, maxExposure);
893 if ((err = is_Exposure(m_hCamera, IS_EXPOSURE_CMD_SET_EXPOSURE,
894 (
void*) &(exposure_ms),
sizeof(exposure_ms))) != IS_SUCCESS) {
895 std::cout <<
"Failed to set exposure to " << exposure_ms <<
896 " ms for " << m_CamListInfo.Model << std::endl;
902 std::cout <<
"Updated exposure: " << ((auto_exposure) ?
"auto" : std::to_string(exposure_ms) +
" ms") <<
903 " for " << m_CamListInfo.Model << std::endl;
909 int setGain(
bool auto_gain,
int master_gain,
bool gain_boost)
911 if (! isConnected()) {
915 INT err = IS_SUCCESS;
918 CAP(master_gain, 0, 100);
920 double pval1 = 0, pval2 = 0;
925 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN,
926 &pval1, &pval2)) != IS_SUCCESS) {
927 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN,
928 &pval1, &pval2)) != IS_SUCCESS) {
930 std::cout << m_CamListInfo.Model <<
" does not support auto gain mode" << std::endl;
932 return IS_NO_SUCCESS;
937 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN,
938 &pval1, &pval2)) != IS_SUCCESS) {
939 if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN,
940 &pval1, &pval2)) != IS_SUCCESS) {
941 std::cout << m_CamListInfo.Model <<
" does not support auto gain mode" << std::endl;
946 if (is_SetGainBoost(m_hCamera, IS_GET_SUPPORTED_GAINBOOST) != IS_SET_GAINBOOST_ON) {
949 if ((err = is_SetGainBoost(m_hCamera,
950 (gain_boost) ? IS_SET_GAINBOOST_ON : IS_SET_GAINBOOST_OFF))
952 std::cout <<
"Failed to " << ((gain_boost) ?
"enable" :
"disable") <<
953 " gain boost for " << m_CamListInfo.Model << std::endl;
958 if ((err = is_SetHardwareGain(m_hCamera, master_gain,
959 IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER)) != IS_SUCCESS) {
960 std::cout <<
"Failed to set manual master gain: " << master_gain <<
" for " << m_CamListInfo.Model << std::endl;
961 return IS_NO_SUCCESS;
967 std::cout <<
"Updated gain for " << m_CamListInfo.Model <<
": auto" << std::endl;
969 std::cout <<
"Updated gain for " << m_CamListInfo.Model <<
": manual master gain " << master_gain << std::endl;
972 std::cout <<
"\n gain boost: " << (gain_boost ?
"enabled" :
"disabled") << std::endl;;
978 void applySubsamplingSettings(
int subsamplingMode,
int nMode)
980 INT ret = IS_SUCCESS;
981 int currentSubsampling = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING);
982 if ((ret = is_SetSubSampling (m_hCamera, subsamplingMode | nMode)) != IS_SUCCESS) {
986 int newSubsampling = is_SetSubSampling(m_hCamera, IS_GET_SUBSAMPLING);
987 if((nMode == IS_SUBSAMPLING_DISABLE) && (currentSubsampling == newSubsampling)) {
990 if ((ret = is_SetSubSampling (m_hCamera, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
996 void setSubsampling(
int factor)
998 if (! isConnected()) {
1002 INT hMode = IS_SUBSAMPLING_DISABLE, vMode = IS_SUBSAMPLING_DISABLE;
1006 hMode = IS_SUBSAMPLING_2X_HORIZONTAL;
1007 vMode = IS_SUBSAMPLING_2X_VERTICAL;
1010 hMode = IS_SUBSAMPLING_3X_HORIZONTAL;
1011 vMode = IS_SUBSAMPLING_3X_VERTICAL;
1014 hMode = IS_SUBSAMPLING_4X_HORIZONTAL;
1015 vMode = IS_SUBSAMPLING_4X_VERTICAL;
1018 hMode = IS_SUBSAMPLING_5X_HORIZONTAL;
1019 vMode = IS_SUBSAMPLING_5X_VERTICAL;
1022 hMode = IS_SUBSAMPLING_6X_HORIZONTAL;
1023 vMode = IS_SUBSAMPLING_6X_VERTICAL;
1026 hMode = IS_SUBSAMPLING_8X_HORIZONTAL;
1027 vMode = IS_SUBSAMPLING_8X_VERTICAL;
1030 hMode = IS_SUBSAMPLING_16X_HORIZONTAL;
1031 vMode = IS_SUBSAMPLING_16X_VERTICAL;
1034 hMode = IS_SUBSAMPLING_DISABLE;
1035 vMode = IS_SUBSAMPLING_DISABLE;
1038 if (m_bLive && m_bLiveStarted) {
1039 is_StopLiveVideo (m_hCamera, IS_WAIT);
1042 INT subsamplingModeH = is_SetSubSampling (m_hCamera, IS_GET_SUBSAMPLING) & IS_SUBSAMPLING_MASK_VERTICAL;
1043 applySubsamplingSettings(subsamplingModeH, hMode);
1045 INT subsamplingModeV = is_SetSubSampling (m_hCamera, IS_GET_SUBSAMPLING) & IS_SUBSAMPLING_MASK_HORIZONTAL;
1046 applySubsamplingSettings(subsamplingModeV, vMode);
1051 void setWhiteBalance(
bool auto_wb)
1053 if (! isConnected()) {
1057 double dblAutoWb = 0.0;
1061 is_SetAutoParameter (m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb, NULL);
1064 is_SetAutoParameter (m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb, NULL);
1068 is_SetAutoParameter (m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb, NULL);
1069 is_SetAutoParameter (m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb, NULL);
1077 ZeroMemory(&m_BufferProps,
sizeof(m_BufferProps));
1080 INT nRet = is_AOI(m_hCamera, IS_AOI_IMAGE_GET_AOI, (
void*)&rectAOI,
sizeof(rectAOI));
1082 if (nRet == IS_SUCCESS) {
1083 width = rectAOI.s32Width;
1084 height = rectAOI.s32Height;
1087 int colormode = is_SetColorMode(m_hCamera, IS_GET_COLOR_MODE);
1089 if(colormode == IS_CM_BGR5_PACKED) {
1090 is_SetColorMode(m_hCamera, IS_CM_BGR565_PACKED);
1091 colormode = IS_CM_BGR565_PACKED;
1092 std::cout <<
"uEye color format 'IS_CM_BGR5_PACKED' actually not supported by vpUeyeGrabber, patched to 'IS_CM_BGR565_PACKED'" << std::endl;
1096 ZeroMemory (&m_BufferProps,
sizeof(m_BufferProps));
1097 m_BufferProps.width = width;
1098 m_BufferProps.height = height;
1099 m_BufferProps.bitspp = getBitsPerPixel(colormode);
1105 std::cout <<
"Capture ready set up." << std::endl;
1111 void setVerbose(
bool verbose)
1113 m_verbose = verbose;
1120 INT m_nBitsPerPixel;
1121 int m_activeCameraSelected;
1122 SENSORINFO m_SensorInfo;
1124 UEYE_CAMERA_INFO m_CamListInfo;
1125 char *m_pLastBuffer;
1126 CameraList *m_cameraList;
1127 struct sBufferProps m_BufferProps;
1128 struct sCameraProps m_CameraProps;
1129 UEYE_IMAGE m_Images[IMAGE_COUNT];
1131 bool m_bLiveStarted;
1141 #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS 1153 : m_impl(new vpUeyeGrabberImpl())
1189 m_impl->acquire(I, timestamp_camera, timestamp_system);
1214 m_impl->acquire(I, timestamp_camera, timestamp_system);
1224 return m_impl->getActiveCameraModel();
1234 return m_impl->getActiveCameraSerialNumber();
1246 return m_impl->getCameraIDList();
1258 return m_impl->getCameraModelList();
1270 return m_impl->getCameraSerialNumberList();
1281 return m_impl->getFramerate();
1293 return m_impl->getFrameHeight();
1305 return m_impl->getFrameWidth();
1314 return m_impl->isConnected();
1324 m_impl->loadParameters(filename);
1352 return (m_impl->setActiveCamera(cam_index) ? false :
true);
1372 return (m_impl->setColorMode(color_mode) ? false :
true);
1390 return (m_impl->setExposure(auto_exposure, exposure_ms) ? false :
true);
1425 return (m_impl->setFrameRate(auto_frame_rate, manual_frame_rate_hz) ? false :
true);
1446 return (m_impl->setGain(auto_gain, master_gain, gain_boost) ? false :
true);
1461 m_impl->setSubsampling(factor);
1476 m_impl->setWhiteBalance(auto_wb);
1486 m_impl->setVerbose(verbose);
1489 #elif !defined(VISP_BUILD_SHARED_LIBS) 1491 void dummy_vpUeyeGrabber(){};
static void BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
void loadParameters(const std::string &filename)
void setWhiteBalance(bool auto_wb)
std::vector< std::string > getCameraSerialNumberList() const
void open(vpImage< unsigned char > &I)
void setSubsampling(int factor)
std::string getActiveCameraModel() const
bool setFrameRate(bool auto_frame_rate, double manual_frame_rate_hz=-1)
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
static void RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size)
Type * bitmap
points toward the bitmap
VISP_EXPORT double measureTimeSecond()
static void BGRaToRGBa(unsigned char *bgra, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
error that can be emited by ViSP classes.
bool setColorMode(const std::string &color_mode)
bool setGain(bool auto_gain, int master_gain=-1, bool gain_boost=false)
static void GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int width, unsigned int height)
unsigned int getFrameWidth() const
static void RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false)
unsigned int getFrameHeight() const
bool setActiveCamera(unsigned int cam_index)
std::vector< unsigned int > getCameraIDList() const
void setVerbose(bool verbose)
static void RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void demosaicRGGBToRGBaBilinear(const uint8_t *rggb, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0)
void acquire(vpImage< unsigned char > &I, double *timestamp_camera=NULL, std::string *timestamp_system=NULL)
static void BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false, unsigned int nThreads=0)
static void BGRaToGrey(unsigned char *bgra, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false, unsigned int nThreads=0)
double getFramerate() const
bool setExposure(bool auto_exposure, double exposure_ms=-1)
std::string getActiveCameraSerialNumber() const
std::vector< std::string > getCameraModelList() const