30 #include <opencv2/core/core.hpp>
31 #include <opencv2/imgproc/imgproc.hpp>
32 # if CV_MAJOR_VERSION >= 3
33 # include <opencv2/core/core_c.h>
42 struct timeval epochtime;
43 struct timespec vsTime;
45 gettimeofday(&epochtime,
nullptr);
46 clock_gettime(CLOCK_MONOTONIC, &vsTime);
48 double uptime = vsTime.tv_sec + vsTime.tv_nsec / 1000000000.0;
49 double epoch = epochtime.tv_sec + epochtime.tv_usec / 1000000.0;
50 return epoch - uptime;
56 if (config.
check(key)) {
63 #define NOT_PRESENT -1
64 int V4L_camera::convertYARP_to_V4L(
int feature)
68 return V4L2_CID_BRIGHTNESS;
71 return V4L2_CID_EXPOSURE;
73 return V4L2_CID_SHARPNESS;
77 return V4L2_CID_SATURATION;
79 return V4L2_CID_GAMMA;
83 return V4L2_CID_IRIS_ABSOLUTE;
137 use_exposure_absolute =
false;
147 configIntrins =
false;
151 pixel_fmt_leo = V4L2_PIX_FMT_SGRBG8;
161 int V4L_camera::convertV4L_to_YARP_format(
int format)
164 case V4L2_PIX_FMT_GREY:
166 case V4L2_PIX_FMT_Y16:
168 case V4L2_PIX_FMT_RGB24:
171 case V4L2_PIX_FMT_BGR24:
173 case V4L2_PIX_FMT_SGRBG8:
175 case V4L2_PIX_FMT_SBGGR8:
177 case V4L2_PIX_FMT_SBGGR16:
179 case V4L2_PIX_FMT_SGBRG8:
181 case V4L2_PIX_FMT_SRGGB8:
183 case V4L2_PIX_FMT_YUV420:
185 case V4L2_PIX_FMT_YUV444:
187 case V4L2_PIX_FMT_YYUV:
189 case V4L2_PIX_FMT_YUV411P:
195 void V4L_camera::populateConfigurations()
197 struct v4l2_fmtdesc fmt;
198 struct v4l2_frmsizeenum frmsize;
199 struct v4l2_frmivalenum frmival;
202 fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
204 while (ioctl(param.
fd, VIDIOC_ENUM_FMT, &fmt) >= 0) {
205 memset(&frmsize, 0,
sizeof(v4l2_frmsizeenum));
206 frmsize.pixel_format = fmt.pixelformat;
208 frmsize.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
209 while (xioctl(param.
fd, VIDIOC_ENUM_FRAMESIZES, &frmsize) >= 0) {
210 if (frmsize.type == V4L2_FRMSIZE_TYPE_DISCRETE) {
211 memset(&frmival, 0,
sizeof(v4l2_frmivalenum));
213 frmival.pixel_format = fmt.pixelformat;
214 frmival.width = frmsize.discrete.width;
215 frmival.height = frmsize.discrete.height;
216 frmsize.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
217 while (xioctl(param.
fd, VIDIOC_ENUM_FRAMEINTERVALS, &frmival) >= 0) {
220 c.
width = frmival.width;
221 c.
height = frmival.height;
222 c.
framerate = (1.0 * frmival.discrete.denominator) / frmival.discrete.numerator;
242 if (!fromConfig(config)) {
253 if (!S_ISCHR(st.st_mode)) {
259 param.
fd = v4l2_open(param.
deviceId.c_str(), O_RDWR | O_NONBLOCK, 0);
262 if (-1 == param.
fd) {
270 v4l2_close(param.
fd);
274 param.
fd = v4l2_open(param.
deviceId.c_str(), O_RDWR | O_NONBLOCK, 0);
277 if (-1 == param.
fd) {
286 enumerate_controls();
288 if (!check_V4L2_control(V4L2_CID_EXPOSURE)) {
289 use_exposure_absolute = check_V4L2_control(V4L2_CID_EXPOSURE_ABSOLUTE);
295 populateConfigurations();
303 if (!white_balance.
isNull()) {
344 bool res = deviceInit();
354 return configFx && configFy;
366 return configIntrins;
372 mirror = (ioctl(param.
fd, V4L2_CID_HFLIP) != 0);
378 int ret = ioctl(param.
fd, V4L2_CID_HFLIP, &mirror);
380 yCError(
USBCAMERA) <<
"V4L2_CID_HFLIP - Unable to mirror image-" << strerror(errno);
388 if (config.
check(
"verbose")) {
392 if (!config.
check(
"width")) {
399 if (!config.
check(
"height")) {
406 if (!config.
check(
"framerate")) {
413 if (!config.
check(
"d")) {
414 yCError(
USBCAMERA) <<
"No camera identifier was specified! (e.g. '--d /dev/video0' on Linux OS)";
421 if (!config.
check(
"camModel")) {
422 yCInfo(
USBCAMERA) <<
"No 'camModel' was specified, working with 'standard' uvc";
425 std::map<std::string, supported_cams>::iterator it = camMap.find(config.
find(
"camModel").
asString());
426 if (it != camMap.end()) {
432 for (it = camMap.begin(); it != camMap.end(); it++) {
441 yCDebug(
USBCAMERA) <<
"-------------------------------\nusbCamera: Using leopard camera!!";
442 bit_shift = config.
check(
"shift",
Value(bit_shift),
"right shift of <n> bits").asInt32();
443 bit_bayer = config.
check(
"bit_bayer",
Value(bit_bayer),
"uses <n> bits bayer conversion").asInt32();
446 pixel_fmt_leo = V4L2_PIX_FMT_SGRBG8;
450 pixel_fmt_leo = V4L2_PIX_FMT_SGRBG10;
454 pixel_fmt_leo = V4L2_PIX_FMT_SGRBG12;
458 yCError(
USBCAMERA) <<
"bayer conversion with " << bit_bayer <<
"not supported";
463 yCDebug(
USBCAMERA) << bit_shift <<
"bits of right shift applied to raw data";
468 if (config.
check(
"crop")) {
475 Value isDual = config.
check(
"dual",
Value(0),
"Is this a dual camera? Two cameras merged into a single frame");
485 if (!config.
check(
"pixelType")) {
496 param.
pixelType = convertV4L_to_YARP_format(param.
src_fmt.fmt.pix.pixelformat);
505 yCError(
USBCAMERA,
"no valid pixel format found!! This should not happen!!");
510 retM = Value::makeList(
"1.0 0.0 0.0 0.0 1.0 0.0 0.0 0.0 1.0");
511 configFx = config.
check(
"horizontalFov");
512 configFy = config.
check(
"verticalFov");
513 configPPx = config.
check(
"principalPointX");
514 configPPy = config.
check(
"principalPointY");
515 configRet = config.
check(
"retificationMatrix");
516 configDistM = config.
check(
"distortionModel");
518 bt = config.
findGroup(
"cameraDistortionModelGroup");
524 "fields k1, k2, k3, t1, t2, name are required when using cameraDistortionModelGroup";
525 configIntrins =
false;
529 configIntrins =
true;
532 configIntrins =
false;
534 param.
horizontalFov = config.
check(
"horizontalFov",
Value(0.0),
"desired horizontal fov of test image").asFloat64();
535 param.
verticalFov = config.
check(
"verticalFov",
Value(0.0),
"desired vertical fov of test image").asFloat64();
536 if (config.
check(
"mirror")) {
539 "mirroring disabled by default")
546 param.
intrinsic.
put(
"focalLengthX", config.
check(
"focalLengthX",
Value(0.0),
"Horizontal component of the focal lenght").asFloat64());
547 param.
intrinsic.
put(
"focalLengthY", config.
check(
"focalLengthY",
Value(0.0),
"Vertical component of the focal lenght").asFloat64());
548 param.
intrinsic.
put(
"principalPointX", config.
check(
"principalPointX",
Value(0.0),
"X coordinate of the principal point").asFloat64());
549 param.
intrinsic.
put(
"principalPointY", config.
check(
"principalPointY",
Value(0.0),
"Y coordinate of the principal point").asFloat64());
550 param.
intrinsic.
put(
"retificationMatrix", config.
check(
"retificationMatrix", *retM,
"Matrix that describes the lens' distortion"));
551 param.
intrinsic.
put(
"distortionModel", config.
check(
"distortionModel",
Value(
""),
"Reference to group of parameters describing the distortion model of the camera").asString());
561 param.
intrinsic.
put(
"k1", bt.
check(
"k1",
Value(0.0),
"Radial distortion coefficient of the lens").asFloat64());
562 param.
intrinsic.
put(
"k2", bt.
check(
"k2",
Value(0.0),
"Radial distortion coefficient of the lens").asFloat64());
563 param.
intrinsic.
put(
"k3", bt.
check(
"k3",
Value(0.0),
"Radial distortion coefficient of the lens").asFloat64());
573 int V4L_camera::getfd()
578 bool V4L_camera::threadInit()
587 void V4L_camera::run()
589 if (full_FrameRead()) {
596 if ((timeElapsed = timeNow - timeStart) > 1.0f) {
597 yCInfo(
USBCAMERA,
"frames acquired %d in %f sec", frameCounter, timeElapsed);
603 void V4L_camera::threadRelease()
612 bool V4L_camera::deviceInit()
614 struct v4l2_capability cap;
615 struct v4l2_cropcap cropcap;
616 struct v4l2_crop crop;
617 struct v4l2_streamparm frameint;
620 if (-1 == xioctl(param.
fd, VIDIOC_QUERYCAP, &cap)) {
621 if (EINVAL == errno) {
631 if (!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE)) {
640 if (!(cap.capabilities & V4L2_CAP_READWRITE)) {
648 if (!(cap.capabilities & V4L2_CAP_STREAMING)) {
661 cropcap.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
663 if (0 == xioctl(param.
fd, VIDIOC_CROPCAP, &cropcap)) {
664 crop.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
665 crop.c = cropcap.defrect;
670 xioctl(param.
fd, VIDIOC_S_CROP, &crop);
676 _v4lconvert_data = v4lconvert_create(param.
fd);
677 if (_v4lconvert_data ==
nullptr) {
678 yCError(
USBCAMERA) <<
"Failed to initialize v4lconvert. Conversion to required format may not work";
697 param.
dst_fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
700 param.
dst_fmt.fmt.pix.field = V4L2_FIELD_NONE;
703 if (v4lconvert_try_format(_v4lconvert_data, &(param.
dst_fmt), &(param.
src_fmt)) != 0) {
704 yCError(
USBCAMERA,
"v4lconvert_try_format -> Error is: %s", v4lconvert_get_error_message(_v4lconvert_data));
712 yCWarning(
USBCAMERA) <<
"Conversion from HW supported configuration into user requested format will require addictional step.\n"
713 <<
"Performance issue may arise.";
719 double inputFF = (double)param.
dst_fmt.fmt.pix.width / (
double)param.
dst_fmt.fmt.pix.height;
722 if (outputFF < inputFF) {
756 if (-1 == xioctl(param.
fd, VIDIOC_S_FMT, ¶m.
src_fmt)) {
762 if (param.
fps != -1) {
766 frameint.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
767 frameint.parm.capture.timeperframe.numerator = 1;
768 frameint.parm.capture.timeperframe.denominator = param.
fps;
769 if (-1 == xioctl(param.
fd, VIDIOC_S_PARM, &frameint)) {
797 readInit(param.
src_fmt.fmt.pix.sizeimage);
805 userptrInit(param.
src_fmt.fmt.pix.sizeimage);
817 bool V4L_camera::deviceUninit()
838 param.
req.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
839 param.
req.memory = V4L2_MEMORY_MMAP;
840 if (xioctl(param.
fd, VIDIOC_REQBUFS, ¶m.
req) < 0) {
841 yCError(
USBCAMERA,
"VIDIOC_REQBUFS - Failed to delete buffers: %s (errno %d)", strerror(errno), errno);
854 if (param.
buffers !=
nullptr) {
874 v4lconvert_destroy(_v4lconvert_data);
890 if (param.
fd != -1) {
894 if (-1 == v4l2_close(param.
fd)) {
984 int V4L_camera::xioctl(
int fd,
int request,
void* argp)
989 r = v4l2_ioctl(fd, request, argp);
990 }
while (-1 == r && EINTR == errno);
1002 void V4L_camera::enumerate_menu()
1010 if (0 == ioctl(param.
fd, VIDIOC_QUERYMENU, &
querymenu)) {
1020 bool V4L_camera::enumerate_controls()
1025 if (0 == ioctl(param.
fd, VIDIOC_QUERYCTRL, &
queryctrl)) {
1026 if (
queryctrl.flags & V4L2_CTRL_FLAG_DISABLED) {
1032 if (
queryctrl.type == V4L2_CTRL_TYPE_MENU) {
1036 if (errno == EINVAL) {
1046 if (0 == ioctl(param.
fd, VIDIOC_QUERYCTRL, &
queryctrl)) {
1047 if (
queryctrl.flags & V4L2_CTRL_FLAG_DISABLED) {
1053 if (
queryctrl.type == V4L2_CTRL_TYPE_MENU) {
1057 if (errno == EINVAL) {
1071 bool V4L_camera::full_FrameRead()
1073 bool got_it =
false;
1074 void* image_ret =
nullptr;
1076 unsigned int numberOfTimeouts;
1082 numberOfTimeouts = 0;
1086 for (
unsigned int i = 0; i < count; i++) {
1088 FD_SET(param.
fd, &fds);
1094 r = select(param.
fd + 1, &fds,
nullptr,
nullptr, &tv);
1097 if (EINTR == errno) {
1101 return image_ret !=
nullptr;
1106 yCWarning(
USBCAMERA,
"timeout while reading image [%d/%d]", numberOfTimeouts, count);
1109 }
else if ((r > 0) && (FD_ISSET(param.
fd, &fds))) {
1129 bool V4L_camera::frameRead()
1132 struct v4l2_buffer buf;
1142 timeStamp.
update(toEpochOffset + buf.timestamp.tv_sec + buf.timestamp.tv_usec / 1000000.0);
1150 buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1151 buf.memory = V4L2_MEMORY_MMAP;
1153 if (-1 == xioctl(param.
fd, VIDIOC_DQBUF, &buf)) {
1166 timeStamp.
update(toEpochOffset + buf.timestamp.tv_sec + buf.timestamp.tv_usec / 1000000.0);
1168 if (-1 == xioctl(param.
fd, VIDIOC_QBUF, &buf)) {
1179 buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1180 buf.memory = V4L2_MEMORY_USERPTR;
1182 if (-1 == xioctl(param.
fd, VIDIOC_DQBUF, &buf)) {
1200 timeStamp.
update(toEpochOffset + buf.timestamp.tv_sec + buf.timestamp.tv_usec / 1000000.0);
1203 if (-1 == xioctl(param.
fd, VIDIOC_QBUF, &buf)) {
1220 void V4L_camera::imagePreProcess()
1227 const uint _pixelNum = param.
src_fmt.fmt.pix.width * param.
src_fmt.fmt.pix.height;
1229 uint16_t* raw_p = (uint16_t*)param.
raw_image;
1230 for (uint i = 0; i < _pixelNum; i++) {
1231 param.
src_image[i] = (
unsigned char)(raw_p[i] >> bit_shift);
1235 param.
src_fmt.fmt.pix.bytesperline = param.
src_fmt.fmt.pix.width;
1236 param.
src_fmt.fmt.pix.pixelformat = pixel_fmt_leo;
1249 void V4L_camera::imageProcess()
1251 static bool initted =
false;
1260 if (v4lconvert_convert((v4lconvert_data*)_v4lconvert_data,
1268 if ((err % 20) == 0) {
1269 yCError(
USBCAMERA,
"error converting \n\t Error message is: %s", v4lconvert_get_error_message(_v4lconvert_data));
1289 cv::resize(img(crop2), img_right, cvSize(param.
user_width / 2, param.
user_height), 0, 0, cv::INTER_CUBIC);
1305 timeTot += timeElapsed;
1307 if ((myCounter % 60) == 0) {
1319 void V4L_camera::captureStop()
1322 int type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1330 ret = xioctl(param.
fd, VIDIOC_STREAMOFF, &type);
1333 yCError(
USBCAMERA,
"VIDIOC_STREAMOFF - Unable to stop capture: %d, %s", errno, strerror(errno));
1343 void V4L_camera::captureStart()
1346 enum v4l2_buf_type type;
1355 struct v4l2_buffer buf;
1358 buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1359 buf.memory = V4L2_MEMORY_MMAP;
1362 if (-1 == xioctl(param.
fd, VIDIOC_QBUF, &buf)) {
1367 type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1369 if (-1 == xioctl(param.
fd, VIDIOC_STREAMON, &type)) {
1377 struct v4l2_buffer buf;
1381 buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1382 buf.memory = V4L2_MEMORY_USERPTR;
1387 if (-1 == xioctl(param.
fd, VIDIOC_QBUF, &buf)) {
1392 type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1394 if (-1 == xioctl(param.
fd, VIDIOC_STREAMON, &type)) {
1403 bool V4L_camera::readInit(
unsigned int buffer_size)
1407 if (param.
buffers ==
nullptr) {
1422 bool V4L_camera::mmapInit()
1428 param.
req.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1429 param.
req.memory = V4L2_MEMORY_MMAP;
1431 if (-1 == xioctl(param.
fd, VIDIOC_REQBUFS, ¶m.
req)) {
1432 if (EINVAL == errno) {
1440 if (param.
req.count < 1) {
1445 if (param.
req.count == 1) {
1446 yCError(
USBCAMERA,
"Only 1 buffer was available, you may encounter performance issue acquiring images from device %s", param.
deviceId.c_str());
1451 if (param.
buffers ==
nullptr) {
1456 struct v4l2_buffer buf;
1461 buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1462 buf.memory = V4L2_MEMORY_MMAP;
1465 if (-1 == xioctl(param.
fd, VIDIOC_QUERYBUF, &buf)) {
1470 param.
buffers[param.
n_buffers].
start = v4l2_mmap(
nullptr, buf.length, PROT_READ | PROT_WRITE, MAP_SHARED, param.
fd, buf.m.offset);
1479 bool V4L_camera::userptrInit(
unsigned int buffer_size)
1481 unsigned int page_size;
1483 page_size = getpagesize();
1484 buffer_size = (buffer_size + page_size - 1) & ~(page_size - 1);
1489 param.
req.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1490 param.
req.memory = V4L2_MEMORY_USERPTR;
1492 if (-1 == xioctl(param.
fd, VIDIOC_REQBUFS, ¶m.
req)) {
1493 if (EINVAL == errno) {
1503 if (param.
buffers ==
nullptr) {
1520 bool V4L_camera::set_V4L2_control(uint32_t
id,
double value,
bool verbatim)
1527 struct v4l2_control control;
1532 if (-1 == ioctl(param.
fd, VIDIOC_QUERYCTRL, &
queryctrl)) {
1533 if (errno != EINVAL) {
1541 if (
queryctrl.flags & V4L2_CTRL_FLAG_DISABLED) {
1545 memset(&control, 0,
sizeof(control));
1548 control.value = value;
1551 if ((V4L2_CID_EXPOSURE ==
id) || (V4L2_CID_EXPOSURE_ABSOLUTE ==
id) || (V4L2_CID_EXPOSURE_AUTO ==
id)) {
1558 if (-1 == ioctl(param.
fd, VIDIOC_S_CTRL, &control)) {
1560 if (errno == ERANGE) {
1561 yCError(
USBCAMERA,
"Normalized input value %f ( equivalent to raw value of %d) was out of range for control %s: Min and Max are: %d - %d", value, control.value,
queryctrl.name,
queryctrl.minimum,
queryctrl.maximum);
1572 bool V4L_camera::check_V4L2_control(uint32_t
id)
1576 struct v4l2_control control;
1578 memset(&control, 0,
sizeof(control));
1584 if (-1 == ioctl(param.
fd, VIDIOC_QUERYCTRL, &
queryctrl)) {
1585 if (errno != EINVAL) {
1593 double V4L_camera::get_V4L2_control(uint32_t
id,
bool verbatim)
1596 struct v4l2_control control;
1598 memset(&control, 0,
sizeof(control));
1604 if (-1 == ioctl(param.
fd, VIDIOC_QUERYCTRL, &
queryctrl)) {
1605 if (errno != EINVAL) {
1612 if (
queryctrl.flags & V4L2_CTRL_FLAG_DISABLED) {
1615 if (-1 == ioctl(param.
fd, VIDIOC_G_CTRL, &control)) {
1621 return control.value;
1625 if ((V4L2_CID_EXPOSURE ==
id) || (V4L2_CID_EXPOSURE_ABSOLUTE ==
id) || (V4L2_CID_EXPOSURE_AUTO ==
id)) {
1643 bool tmpAuto(
false);
1644 bool tmpOnce(
false);
1648 tmpMan = check_V4L2_control(V4L2_CID_RED_BALANCE) && check_V4L2_control(V4L2_CID_BLUE_BALANCE);
1649 tmpOnce = check_V4L2_control(V4L2_CID_DO_WHITE_BALANCE);
1650 tmpAuto = check_V4L2_control(V4L2_CID_AUTO_WHITE_BALANCE);
1654 tmpMan = check_V4L2_control(V4L2_CID_EXPOSURE) || check_V4L2_control(V4L2_CID_EXPOSURE_ABSOLUTE);
1655 tmpAuto = check_V4L2_control(V4L2_CID_EXPOSURE_AUTO);
1659 tmpMan = check_V4L2_control(convertYARP_to_V4L(feature));
1663 *_hasFeature = tmpMan || tmpOnce || tmpAuto;
1672 if (use_exposure_absolute) {
1673 ret = set_V4L2_control(V4L2_CID_EXPOSURE_ABSOLUTE, value);
1675 ret = set_V4L2_control(V4L2_CID_EXPOSURE, value);
1680 ret = set_V4L2_control(convertYARP_to_V4L(feature), value);
1691 if (use_exposure_absolute) {
1692 tmp = get_V4L2_control(V4L2_CID_EXPOSURE_ABSOLUTE);
1694 tmp = get_V4L2_control(V4L2_CID_EXPOSURE);
1699 tmp = get_V4L2_control(convertYARP_to_V4L(feature));
1715 ret &= set_V4L2_control(V4L2_CID_AUTO_WHITE_BALANCE,
false);
1716 ret &= set_V4L2_control(V4L2_CID_AUTO_N_PRESET_WHITE_BALANCE, V4L2_WHITE_BALANCE_MANUAL);
1717 ret &= set_V4L2_control(V4L2_CID_RED_BALANCE, value1);
1718 ret &= set_V4L2_control(V4L2_CID_BLUE_BALANCE, value2);
1727 *value1 = get_V4L2_control(V4L2_CID_RED_BALANCE);
1728 *value2 = get_V4L2_control(V4L2_CID_BLUE_BALANCE);
1729 return !((*value1 == -1) || (*value2 == -1));
1742 if (
hasAuto(feature, &_hasAuto)) {
1768 tmp = set_V4L2_control(V4L2_CID_AUTO_WHITE_BALANCE, onoff);
1770 isActive_vector[feature] = onoff;
1776 set_V4L2_control(V4L2_LOCK_EXPOSURE,
false);
1780 tmp = set_V4L2_control(V4L2_CID_EXPOSURE_AUTO, V4L2_EXPOSURE_AUTO);
1782 tmp = set_V4L2_control(V4L2_CID_EXPOSURE_AUTO, V4L2_EXPOSURE_MANUAL);
1786 isActive_vector[feature] = onoff;
1789 bool man = set_V4L2_control(V4L2_CID_EXPOSURE_AUTO, V4L2_EXPOSURE_MANUAL);
1791 man = set_V4L2_control(V4L2_CID_EXPOSURE_AUTO, V4L2_EXPOSURE_SHUTTER_PRIORITY,
true);
1796 set_V4L2_control(V4L2_LOCK_EXPOSURE,
true);
1797 isActive_vector[feature] = onoff;
1803 isActive_vector[feature] =
true;
1806 isActive_vector[feature] =
false;
1817 double tmp = get_V4L2_control(V4L2_CID_AUTO_WHITE_BALANCE);
1828 bool _hasMan(
false);
1829 bool _hasMan2(
false);
1831 double _hasAuto = get_V4L2_control(V4L2_CID_EXPOSURE_AUTO,
true);
1833 *_isActive = (_hasAuto == V4L2_EXPOSURE_AUTO) || _hasMan || _hasMan2;
1849 *_hasAuto = check_V4L2_control(V4L2_CID_AUTO_WHITE_BALANCE);
1853 *_hasAuto = check_V4L2_control(V4L2_CID_AUTOBRIGHTNESS);
1857 *_hasAuto = check_V4L2_control(V4L2_CID_AUTOGAIN);
1861 *_hasAuto = check_V4L2_control(V4L2_CID_EXPOSURE_AUTO);
1865 *_hasAuto = check_V4L2_control(V4L2_CID_HUE_AUTO);
1878 *_hasManual = check_V4L2_control(V4L2_CID_RED_BALANCE) && check_V4L2_control(V4L2_CID_BLUE_BALANCE);
1883 *_hasManual = check_V4L2_control(V4L2_CID_EXPOSURE) || check_V4L2_control(V4L2_CID_EXPOSURE_ABSOLUTE);
1894 *_hasOnePush = check_V4L2_control(V4L2_CID_DO_WHITE_BALANCE);
1898 *_hasOnePush =
false;
1910 ret = set_V4L2_control(V4L2_CID_AUTO_WHITE_BALANCE,
true);
1912 ret = set_V4L2_control(V4L2_CID_AUTO_WHITE_BALANCE,
false);
1918 hasAuto(V4L2_CID_EXPOSURE_AUTO, &_tmpAuto);
1922 ret = set_V4L2_control(V4L2_CID_EXPOSURE_AUTO,
true);
1924 ret = set_V4L2_control(V4L2_CID_EXPOSURE_AUTO,
false);
1934 ret = set_V4L2_control(V4L2_CID_AUTOGAIN,
true);
1937 ret = set_V4L2_control(V4L2_CID_AUTOGAIN,
false);
1948 ret = set_V4L2_control(V4L2_CID_AUTOBRIGHTNESS,
true);
1950 ret = set_V4L2_control(V4L2_CID_AUTOBRIGHTNESS,
false);
1960 ret = set_V4L2_control(V4L2_CID_HUE_AUTO,
true);
1962 ret = set_V4L2_control(V4L2_CID_HUE_AUTO,
false);
1967 yCError(
USBCAMERA) <<
"Feature " << feature <<
" does not support auto mode";
1979 double ret = get_V4L2_control(V4L2_CID_AUTO_WHITE_BALANCE);
1986 double ret = get_V4L2_control(V4L2_CID_EXPOSURE_AUTO);
1992 if (
ret == V4L2_EXPOSURE_MANUAL) {
2006 double ret = get_V4L2_control(V4L2_CID_AUTOBRIGHTNESS);
2017 double ret = get_V4L2_control(V4L2_CID_AUTOGAIN);
2028 double ret = get_V4L2_control(V4L2_CID_HUE_AUTO);
2044 return set_V4L2_control(V4L2_CID_DO_WHITE_BALANCE,
true);
@ YARP_FEATURE_BRIGHTNESS
@ YARP_FEATURE_WHITE_BALANCE
@ YARP_FEATURE_SATURATION
const yarp::os::LogComponent & USBCAMERA()
struct v4l2_queryctrl queryctrl
static double getEpochTimeShift()
struct v4l2_querymenu querymenu
#define DEFAULT_FRAMERATE
#define VIDIOC_REQBUFS_COUNT
bool getMode(int feature, FeatureMode *mode) override
Get the current mode for the feature.
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
int getRgbWidth() override
Return the width of each frame.
bool setMode(int feature, FeatureMode mode) override
Set the requested mode for the feature.
yarp::os::Stamp getLastInputStamp() override
Return the time stamp relative to the last acquisition.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
bool hasOnePush(int feature, bool *_hasOnePush) override
Check if the requested feature has the 'onePush' mode.
bool close() override
close device
bool hasFeature(int feature, bool *hasFeature) override
Check if camera has the requested feature (saturation, brightness ...
bool getRgbIntrinsicParam(yarp::os::Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool hasOnOff(int feature, bool *_hasOnOff) override
Check if the camera has the ability to turn on/off the requested feature.
bool setActive(int feature, bool onoff) override
Set the requested feature on or off.
bool getCameraDescription(CameraDescriptor *camera) override
Get a basic description of the camera hw.
int getRgbHeight() override
Return the height of each frame.
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool hasAuto(int feature, bool *_hasAuto) override
Check if the requested feature has the 'auto' mode.
int width() const override
Return the width of each frame.
bool getFeature(int feature, double *value) override
Get the current value for the requested feature.
bool setOnePush(int feature) override
Set the requested feature to a value (saturation, brightness ...
bool setFeature(int feature, double value) override
Set the requested feature to a value (saturation, brightness ...
bool getActive(int feature, bool *_isActive) override
Get the current status of the feature, on or off.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool getRgbBuffer(unsigned char *buffer) override
Get a rgb buffer from the frame grabber, if required demosaicking/color reconstruction is applied.
int height() const override
Return the height of each frame.
int getRawBufferSize() override
Get the size of the card's internal buffer, the user should use this method to allocate the storage t...
bool getRawBuffer(unsigned char *buffer) override
Get the raw buffer from the frame grabber.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool open(yarp::os::Searchable &config) override
open device
bool hasManual(int feature, bool *_hasManual) override
Check if the requested feature has the 'manual' mode.
FeatureMode toFeatureMode(bool _auto)
A simple collection of objects that can be described and transmitted in a portable way.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
bool isNull() const override
Checks if the object is invalid.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
An abstraction for a periodic thread.
bool start()
Call this to start the thread.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
A class for storing options and configuration information.
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
A base class for nested structures that can be searched.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
void wait()
Decrement the counter, even if we must wait to do that.
void post()
Increment the counter.
An abstraction for a time stamp and/or sequence number.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
A single value (typically within a Bottle).
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual bool asBool() const
Get boolean value.
virtual std::int32_t asInt32() const
Get 32-bit integer value.
bool isNull() const override
Checks if the object is invalid.
virtual std::string asString() const
Get string value.
void push_back(const T &elem)
Push a new element in the vector: size is changed.
#define YARP_NULLPTR
Expands to either the standard nullptr or to 0 elsewhere.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
@ VOCAB_PIXEL_ENCODING_BAYER_BGGR16
@ VOCAB_PIXEL_ENCODING_BAYER_BGGR8
@ VOCAB_PIXEL_ENCODING_BAYER_RGGB8
@ VOCAB_PIXEL_ENCODING_BAYER_GRBG8
@ VOCAB_PIXEL_ENCODING_BAYER_GBRG8
void list_cap_v4l2(int fd)
void query_current_image_fmt_v4l2(int fd)
An interface for the device drivers.
double now()
Return the current time in seconds, relative to an arbitrary starting point.
void delay(double seconds)
Wait for a certain number of seconds.
An interface to the operating system, including Port based communication.
int stat(const char *path)
Portable wrapper for the stat() function.
std::string deviceDescription
struct v4l2_format dst_fmt
unsigned char * read_image
yarp::sig::VectorOf< yarp::dev::CameraConfig > configurations
struct v4l2_format src_fmt
unsigned char * raw_image
unsigned char * dst_image_rgb
yarp::os::Property intrinsic
struct v4l2_requestbuffers req
unsigned char * src_image
unsigned int dst_image_size_rgb
unsigned int src_image_size
unsigned int raw_image_size
Struct describing a possible camera configuration.
YarpVocabPixelTypesEnum pixelCoding