37 #include <sys/ioctl.h> 38 #include <sys/sysmacros.h> 39 #include <linux/usb/video.h> 40 #include <linux/uvcvideo.h> 41 #include <linux/videodev2.h> 45 #include <sys/signalfd.h> 47 #pragma GCC diagnostic ignored "-Woverflow" 51 #include "../tm2/tm-boot.h" 66 memset(&fl, 0,
sizeof(fl));
67 fl.l_whence = SEEK_CUR;
74 return fcntl(fd, F_SETLK64, &fl);
79 return fcntl(fd, F_SETLKW64, &fl);
84 return fcntl(fd, F_SETLK64, &fl);
88 if (fcntl(fd, F_GETLK64, &fl) == -1)
return -1;
89 if (fl.l_type == F_UNLCK || fl.l_pid == getpid())
return 0;
100 return lockf64(
fd,
cmd, length);
113 : _device_path(device_path),
116 _object_lock_counter(0)
154 auto ret = lockf(
_fildes, F_TLOCK, 0);
178 auto ret = lockf(
_fildes, F_LOCK, 0);
205 auto ret = lockf(
_fildes, F_ULOCK, 0);
207 err_msg =
to_string() <<
"lockf(...) failed";
212 err_msg =
to_string() <<
"close(...) failed";
219 if (!err_msg.empty())
224 static int xioctl(
int fh,
unsigned long request,
void *
arg)
228 r = ioctl(fh, request, arg);
229 }
while (r < 0 && errno == EINTR);
234 : _type(type), _use_memory_map(use_memory_map), _index(index)
236 v4l2_buffer
buf = {};
238 buf.memory = use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
240 if(
xioctl(fd, VIDIOC_QUERYBUF, &buf) < 0)
251 PROT_READ | PROT_WRITE, MAP_SHARED,
267 v4l2_buffer
buf = {};
275 buf.m.userptr =
reinterpret_cast<unsigned long>(
_start);
277 if(
xioctl(fd, VIDIOC_QBUF, &buf) < 0)
280 LOG_DEBUG_V4L(
"prepare_for_streaming fd " << std::dec << fd);
324 LOG_ERROR(
"xioctl(VIDIOC_QBUF) failed when requesting new frame! fd: " << fd <<
" error: " << strerror(errno));
334 std::shared_ptr<platform::buffer> data_buf
343 this->
buffers.at(buf_type)._managed =
true;
347 buffers.at(buf_type)._file_desc = file_desc;
348 buffers.at(buf_type)._managed =
false;
349 buffers.at(buf_type)._data_buf = data_buf;
350 buffers.at(buf_type)._dq_buf = v4l_buf;
358 if (
buf._data_buf && (
buf._file_desc >= 0))
359 buf._data_buf->request_next_frame(
buf._file_desc);
367 void* md_start =
nullptr;
372 static const int d4xx_md_size = 248;
379 auto md_appendix_sz = 0L;
380 if (compressed && (dq.bytesused < fr_payload_size))
381 md_appendix_sz = d4xx_md_size;
383 md_appendix_sz = long(dq.bytesused) - fr_payload_size;
385 if (md_appendix_sz >0 )
388 md_size = (*(
static_cast<uint8_t*
>(md_start)));
389 int md_flags = (*(
static_cast<uint8_t*
>(md_start)+1));
391 if ((md_appendix_sz != md_size) || (!
val_in_range(md_flags, {0x8e, 0x8f})))
399 if (
nullptr == md_start)
403 set_md_attributes(static_cast<uint8_t>(md_size),md_start);
411 LOG_ERROR(
"Non-sequential Video and Metadata v4l buffers");
429 char usb_actual_path[PATH_MAX] = {0};
430 if (realpath(path.c_str(), usb_actual_path) !=
nullptr)
434 if(!(std::ifstream(path +
"/version") >> val))
438 [&
val](
const std::pair<usb_spec, std::string>& kpv){
return (std::string::npos !=val.find(kpv.second));});
449 std::unique_ptr<int, std::function<void(int*)> >
fd(
450 new int (open(dev_name.c_str(), O_RDWR | O_NONBLOCK, 0)),
451 [](
int*
d){
if (
d && (*
d)) {::close(*
d); }
delete d; });
456 v4l2_capability
cap = {};
457 if(
xioctl(*
fd, VIDIOC_QUERYCAP, &cap) < 0)
465 return cap.device_caps;
481 v4l2_memory mem_type, v4l2_buf_type
type)
483 struct v4l2_requestbuffers req = {
count,
type, mem_type, {}};
485 if(
xioctl(fd, VIDIOC_REQBUFS, &req) < 0)
488 LOG_ERROR(dev_name +
" does not support memory mapping");
499 DIR *
dir = opendir(
"/sys/class/video4linux");
502 LOG_INFO(
"Cannot access /sys/class/video4linux");
507 typedef std::pair<uvc_device_info,std::string> node_info;
508 std::vector<node_info> uvc_nodes,uvc_devices;
510 while (dirent *
entry = readdir(dir))
513 if(name ==
"." || name ==
"..")
continue;
518 char buff[PATH_MAX] = {0};
519 if (realpath(path.c_str(), buff) !=
nullptr)
522 if (real_path.find(
"virtual") != std::string::npos)
531 auto dev_name =
"/dev/" +
name;
534 if(stat(dev_name.c_str(), &
st) < 0)
538 if(!S_ISCHR(st.st_mode))
542 std::ostringstream ss; ss <<
"/sys/dev/char/" <<
major(st.st_rdev) <<
":" <<
minor(st.st_rdev) <<
"/device/";
543 auto path = ss.str();
544 auto valid_path =
false;
547 if(std::ifstream(path +
"busnum") >> busnum)
549 if(std::ifstream(path +
"devnum") >> devnum)
551 if(std::ifstream(path +
"devpath") >> devpath)
565 LOG_INFO(
"Failed to read busnum/devnum. Device Path: " << path);
571 if(!(std::ifstream(
"/sys/class/video4linux/" + name +
"/device/modalias") >> modalias))
573 if(modalias.size() < 14 || modalias.substr(0,5) !=
"usb:v" || modalias[9] !=
'p')
579 if(!(std::ifstream(
"/sys/class/video4linux/" + name +
"/device/bInterfaceNumber") >> std::hex >> mi))
597 info.unique_id = busnum +
"-" + devpath +
"-" + devnum;
598 info.conn_spec = usb_specification;
601 uvc_nodes.emplace_back(
info, dev_name);
603 catch(
const std::exception &
e)
605 LOG_INFO(
"Not a USB video device: " << e.what());
615 std::stringstream index_l(lhs.first.id.substr(lhs.first.id.find_first_of(
"0123456789")));
616 std::stringstream index_r(rhs.first.id.substr(rhs.first.id.find_first_of(
"0123456789")));
617 int left_id = 0; index_l >> left_id;
618 int right_id = 0; index_r >> right_id;
619 return left_id < right_id;
623 for (
auto&& cur_node : uvc_nodes)
628 uvc_devices.emplace_back(cur_node);
631 if (uvc_devices.empty())
633 LOG_ERROR(
"uvc meta-node with no video streaming node encountered: " <<
std::string(cur_node.first));
638 auto uvc_node = uvc_devices.back();
646 if (uvc_node.first.has_metadata_node)
648 LOG_ERROR(
"Metadata node for uvc device: " <<
std::string(uvc_node.first) <<
" was previously assigned ");
653 uvc_node.first.has_metadata_node =
true;
654 uvc_node.first.metadata_node_id = cur_node.first.id;
655 uvc_devices.back() = uvc_node;
658 catch(
const std::exception &
e)
660 LOG_ERROR(
"Failed to map meta-node " <<
std::string(cur_node.first) <<
", error encountered: " << e.what());
667 for (
auto&&
dev : uvc_devices)
670 catch(
const std::exception &
e)
672 LOG_ERROR(
"Registration of UVC device failed: " << e.what());
677 :
_name(
""), _info(),
678 _is_capturing(false),
718 v4l2_fmtdesc pixel_format = {};
719 pixel_format.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
721 while (ioctl(
_fd, VIDIOC_ENUM_FMT, &pixel_format) == 0)
723 v4l2_frmsizeenum frame_size = {};
724 frame_size.pixel_format = pixel_format.pixelformat;
728 if (pixel_format.pixelformat == 0)
733 static const std::set<std::string> pending_formats = {
734 "00000050-0000-0010-8000-00aa003",
735 "00000032-0000-0010-8000-00aa003",
739 pending_formats.end(),
740 (
const char*)pixel_format.description) ==
741 pending_formats.end())
747 if (std::regex_search(s.begin(), s.end(), match, rgx))
749 std::stringstream ss;
752 ss >> std::hex >>
id;
755 if (fourcc == profile.
format)
758 <<
"' is not natively supported by the running Linux kernel and likely requires a patch");
763 ++pixel_format.index;
768 v4l2_streamparm parm = {};
769 parm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
770 if(
xioctl(
_fd, VIDIOC_G_PARM, &parm) < 0)
773 parm.parm.capture.timeperframe.numerator = 1;
774 parm.parm.capture.timeperframe.denominator = profile.
fps;
775 if(
xioctl(
_fd, VIDIOC_S_PARM, &parm) < 0)
860 char fourcc_buff[
sizeof(device_fourcc)+1];
862 fourcc_buff[
sizeof(device_fourcc)] = 0;
884 auto ms = duration_cast<milliseconds>(
now.time_since_epoch()) % 1000;
887 auto timer = system_clock::to_time_t(
now);
890 std::tm bt = *std::localtime(&timer);
892 std::ostringstream oss;
894 oss << std::put_time(&bt,
"%H:%M:%S");
895 oss <<
'.' << std::setfill(
'0') << std::setw(3) << ms.count();
908 struct timespec mono_time;
909 int ret = clock_gettime(CLOCK_MONOTONIC, &mono_time);
912 struct timeval expiration_time = { mono_time.tv_sec + 5, mono_time.tv_nsec / 1000 };
919 struct timeval remaining;
920 ret = clock_gettime(CLOCK_MONOTONIC, &mono_time);
923 struct timeval current_time = { mono_time.tv_sec, mono_time.tv_nsec / 1000 };
924 timersub(&expiration_time, ¤t_time, &remaining);
925 if (timercmp(¤t_time, &expiration_time, <)) {
926 val = select(
_max_fd + 1, &fds,
nullptr,
nullptr, &remaining);
934 LOG_DEBUG_V4L(
"Select interrupted, val = " << val <<
", error = " << errno);
935 }
while (val < 0 && errno == EINTR);
959 LOG_ERROR(
"Stop pipe was signalled during streaming");
965 bool md_extracted =
false;
966 bool keep_md =
false;
967 bool wa_applied =
false;
977 std::unique_ptr<int, std::function<void(int*)> > md_poller(
new int(0),
978 [
this,&buf_mgr,&md_extracted,&keep_md,&fds](
int*
d)
990 LOG_DEBUG_V4L(
"Poller stores buf for fd " << std::dec << mdb._file_desc
991 <<
" ,seq = " << mdb._dq_buf.sequence <<
" v4l_buf " << mdb._dq_buf.index
1001 if (md_buf._data_buf)
1002 md_buf._data_buf->request_next_frame(md_buf._file_desc,
true);
1009 if(FD_ISSET(
_fd, &fds))
1012 v4l2_buffer
buf = {};
1013 buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1014 buf.memory =
_use_memory_map ? V4L2_MEMORY_MMAP : V4L2_MEMORY_USERPTR;
1019 LOG_DEBUG_V4L(
"Dequeued buf " << std::dec << buf.index <<
" for fd " <<
_fd <<
" seq " << buf.sequence);
1026 if(buf.bytesused == 0)
1028 LOG_DEBUG_V4L(
"Empty video frame arrived, index " << buf.index);
1037 if (partial_frame || overflow_frame)
1040 std::stringstream
s;
1043 s <<
"Incomplete video frame detected!\nSize " << buf.bytesused
1048 LOG_ERROR(
"Corrupted UVC frame data, underflow and overflow reported:\n" << s.str().c_str());
1054 s <<
"overflow video frame detected!\nSize " << buf.bytesused
1057 LOG_WARNING(
"Incomplete frame received: " << s.str());
1064 LOG_WARNING(
"Metadata was present when partial frame arrived, mark md as extracted");
1065 md_extracted =
true;
1066 LOG_DEBUG_V4L(
"Discarding md due to invalid video payload");
1068 md_buf._data_buf->request_next_frame(md_buf._file_desc,
true);
1073 auto timestamp = (double)buf.timestamp.tv_sec*1000.f + (
double)buf.timestamp.tv_usec/1000.f;
1078 md_extracted =
true;
1103 LOG_WARNING(
"Video frame dropped, video and metadata buffers inconsistency");
1116 LOG_DEBUG(
"FD_ISSET: no data on video node sink");
1122 LOG_WARNING(
"Frames didn't arrived within 5 seconds");
1155 static_cast<uint16_t>(size),
const_cast<uint8_t *
>(
data)};
1156 if(
xioctl(
_fd, UVCIOC_CTRL_QUERY, &q) < 0)
1158 if (errno == EIO || errno == EAGAIN)
1169 static_cast<uint16_t>(size),
const_cast<uint8_t *
>(
data)};
1170 if(
xioctl(
_fd, UVCIOC_CTRL_QUERY, &q) < 0)
1172 if (errno == EIO || errno == EAGAIN || errno == EBUSY)
1189 struct uvc_xu_control_query xquery = {};
1190 memset(&xquery, 0,
sizeof(xquery));
1195 xquery.selector = control;
1196 xquery.unit = xu.
unit;
1197 xquery.data = (__u8 *)&size;
1199 if(-1 == ioctl(
_fd,UVCIOC_CTRL_QUERY,&xquery)){
1205 std::vector<uint8_t>
buf;
1206 auto buf_size = std::max((
size_t)len,
sizeof(__u32));
1207 buf.resize(buf_size);
1211 xquery.selector = control;
1212 xquery.unit = xu.
unit;
1213 xquery.data = buf.data();
1214 if(-1 == ioctl(
_fd,UVCIOC_CTRL_QUERY,&xquery)){
1217 result.min.resize(buf_size);
1222 xquery.selector = control;
1223 xquery.unit = xu.
unit;
1224 xquery.data = buf.data();
1225 if(-1 == ioctl(
_fd,UVCIOC_CTRL_QUERY,&xquery)){
1228 result.max.resize(buf_size);
1233 xquery.selector = control;
1234 xquery.unit = xu.
unit;
1235 xquery.data = buf.data();
1236 if(-1 == ioctl(
_fd,UVCIOC_CTRL_QUERY,&xquery)){
1239 result.def.resize(buf_size);
1244 xquery.selector = control;
1245 xquery.unit = xu.
unit;
1246 xquery.data = buf.data();
1247 if(-1 == ioctl(
_fd,UVCIOC_CTRL_QUERY,&xquery)){
1250 result.step.resize(buf_size);
1258 struct v4l2_control control = {
get_cid(opt), 0};
1259 if (
xioctl(
_fd, VIDIOC_G_CTRL, &control) < 0)
1261 if (errno == EIO || errno == EAGAIN)
1268 value = control.value;
1275 struct v4l2_control control = {
get_cid(opt), value};
1277 if (
xioctl(
_fd, VIDIOC_S_CTRL, &control) < 0)
1279 if (errno == EIO || errno == EAGAIN)
1293 static const int32_t min = 0, max = 1, step = 1, def = 1;
1299 struct v4l2_queryctrl query = {};
1301 if (
xioctl(
_fd, VIDIOC_QUERYCTRL, &query) < 0)
1306 query.minimum = query.maximum = 0;
1316 std::vector<stream_profile> results;
1320 v4l2_fmtdesc pixel_format = {};
1321 pixel_format.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1322 while (ioctl(
_fd, VIDIOC_ENUM_FMT, &pixel_format) == 0)
1324 v4l2_frmsizeenum frame_size = {};
1325 frame_size.pixel_format = pixel_format.pixelformat;
1329 if (pixel_format.pixelformat == 0)
1334 std::set<std::string> known_problematic_formats = {
1335 "00000050-0000-0010-8000-00aa003",
1336 "00000032-0000-0010-8000-00aa003",
1339 if (
std::find(known_problematic_formats.begin(),
1340 known_problematic_formats.end(),
1341 (
const char*)pixel_format.description) ==
1342 known_problematic_formats.end())
1348 if (std::regex_search(s.begin(), s.end(), match, rgx))
1350 std::stringstream ss;
1353 ss >> std::hex >>
id;
1357 LOG_WARNING(
"Pixel format " << pixel_format.description <<
" likely requires patch for fourcc code " << format_str <<
"!");
1363 LOG_DEBUG(
"Recognized pixel-format " << pixel_format.description);
1366 while (ioctl(
_fd, VIDIOC_ENUM_FRAMESIZES, &frame_size) == 0)
1368 v4l2_frmivalenum frame_interval = {};
1369 frame_interval.pixel_format = pixel_format.pixelformat;
1370 frame_interval.width = frame_size.discrete.width;
1371 frame_interval.height = frame_size.discrete.height;
1372 while (ioctl(
_fd, VIDIOC_ENUM_FRAMEINTERVALS, &frame_interval) == 0)
1374 if (frame_interval.type == V4L2_FRMIVAL_TYPE_DISCRETE)
1376 if (frame_interval.discrete.numerator != 0)
1379 static_cast<float>(frame_interval.discrete.denominator) /
1380 static_cast<float>(frame_interval.discrete.numerator);
1384 p.width = frame_size.discrete.width;
1385 p.height = frame_size.discrete.height;
1387 if (fourcc != 0) results.push_back(
p);
1391 ++frame_interval.index;
1397 ++pixel_format.index;
1442 catch (
const std::exception& ex)
1471 V4L2_BUF_TYPE_VIDEO_CAPTURE);
1495 _fd = open(
_name.c_str(), O_RDWR | O_NONBLOCK, 0);
1508 v4l2_capability
cap = {};
1509 if(
xioctl(
_fd, VIDIOC_QUERYCAP, &cap) < 0)
1516 if(!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE))
1519 if(!(cap.capabilities & V4L2_CAP_STREAMING))
1523 v4l2_cropcap cropcap = {};
1524 cropcap.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1525 if(
xioctl(
_fd, VIDIOC_CROPCAP, &cropcap) == 0)
1527 v4l2_crop
crop = {};
1528 crop.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1529 crop.c = cropcap.defrect;
1530 if(
xioctl(
_fd, VIDIOC_S_CROP, &crop) < 0)
1558 v4l2_format
fmt = {};
1559 fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
1560 fmt.fmt.pix.width = profile.
width;
1561 fmt.fmt.pix.height = profile.
height;
1563 fmt.fmt.pix.field = V4L2_FIELD_NONE;
1569 LOG_INFO(
"Video node was successfully configured to " <<
fourcc_to_string(fmt.fmt.pix.pixelformat) <<
" format" <<
", fd " << std::dec <<
_fd);
1577 _md_name(info.metadata_node_id)
1650 v4l2_capability
cap = {};
1662 if(!(cap.capabilities & V4L2_CAP_STREAMING))
1696 memcpy(
fmt.fmt.raw_data,&request,
sizeof(request));
1728 if(FD_ISSET(
_md_fd, &fds))
1733 LOG_WARNING(
"Metadata override requested but avoided skipped");
1750 auto hwts = *(
uint32_t*)((mdbuf+2));
1751 auto fn = *(
uint32_t*)((mdbuf+38));
1753 <<
" fn " << fn <<
" hw ts " << hwts
1754 <<
" v4lbuf ts usec " <<
buf.timestamp.tv_usec);
1760 LOG_INFO(
"Metadata frame arrived in idle mode.");
1764 if (
buf.bytesused > uvc_md_start_offset )
1775 LOG_DEBUG_V4L(
"Invalid md size: bytes used = " <<
buf.bytesused <<
" ,start offset=" << uvc_md_start_offset);
1777 if(
buf.bytesused > 0)
1779 std::stringstream
s;
1780 s <<
"Invalid metadata payload, size " <<
buf.bytesused;
1791 auto v4l_uvc_dev = (!info.
has_metadata_node) ? std::make_shared<v4l_uvc_device>(info) :
1792 std::make_shared<v4l_uvc_meta_device>(
info);
1794 return std::make_shared<platform::retry_controls_work_around>(v4l_uvc_dev);
1799 std::vector<uvc_device_info> uvc_nodes;
1803 uvc_nodes.push_back(i);
1813 return std::make_shared<platform::command_transfer_usb>(
dev);
1823 std::this_thread::sleep_for(std::chrono::milliseconds(2000));
1826 return device_infos;
1831 return std::make_shared<v4l_hid_device>(
info);
1836 std::vector<hid_device_info> results;
1838 results.push_back(hid_dev_info);
1845 return std::make_shared<os_time_service>();
1850 return std::make_shared<polling_device_watcher>(
this);
1855 return std::make_shared<v4l_backend>();
static const textual_icon lock
std::istringstream istringstream
GLuint const GLchar * name
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
#define V4L2_META_FMT_D4XX
bool val_in_range(const T &val, const std::initializer_list< T > &list)
GLsizei const GLchar *const * path
#define V4L2_CAP_META_CAPTURE
#define V4L2_META_FMT_UVC
const uint8_t MAX_META_DATA_SIZE
GLsizei const GLchar *const * string
void sort(sort_type m_sort_type, const std::string &in, const std::string &out)
const size_t MAX_DEV_PARENT_DIR
GLenum GLuint GLenum GLsizei const GLchar * buf
def info(name, value, persistent=False)
constexpr auto LOCAL_V4L2_BUF_TYPE_META_CAPTURE
#define LOG_DEBUG_V4L(...)
double monotonic_to_realtime(double monotonic)
LOG_INFO("Log message using LOG_INFO()")
GLdouble GLdouble GLdouble q
GLbitfield GLuint64 timeout
GLenum GLuint GLenum GLsizei length
void copy(void *dst, void const *src, size_t size)
std::string to_string(T value)