Tx2: 4.3 h.264 yuv camera recorder [ERROR] (NvV4l2ElementPlane.cpp:178) <enc0> Capture Plane:Error while DQing buffer: Broken pipe

I am trying to record through a yuv camera sensor(tc358773)
here is the command but it always report dq buffer error.

sudo ./camera_v4l2_cuda -d /dev/video0 -s 1920x1080 -f UYVY -n 30 -c

open /dev/ttyTHS1 OK
[got 1 bytes]:
Opening in BLOCKING MODE
NvMMLiteOpen : Block : BlockType = 4
===== NVMEDIA: NVENC =====
NvMMLiteBlockCreate : Block : BlockType = 4
875967048
842091865
0
H264: Profile = 100, Level = 50
1
2
3
4
5
INFO: camera_initialize(): (line:606) Camera ouput format: (1920 x 1080) stride: 3840, imagesize: 4147200, frate: 0 / 0
INFO: init_components(): (line:618) Initialize v4l2 components successfully
WARN: request_camera_buff(): (line:656) Camera v4l2 buf length is not expected
WARN: request_camera_buff(): (line:656) Camera v4l2 buf length is not expected
WARN: request_camera_buff(): (line:656) Camera v4l2 buf length is not expected
WARN: request_camera_buff(): (line:656) Camera v4l2 buf length is not expected
WARN: request_camera_buff(): (line:656) Camera v4l2 buf length is not expected
WARN: request_camera_buff(): (line:656) Camera v4l2 buf length is not expected
WARN: request_camera_buff(): (line:656) Camera v4l2 buf length is not expected
WARN: request_camera_buff(): (line:656) Camera v4l2 buf length is not expected
WARN: request_camera_buff(): (line:656) Camera v4l2 buf length is not expected
WARN: request_camera_buff(): (line:656) Camera v4l2 buf length is not expected
INFO: prepare_buffers(): (line:771) Succeed in preparing stream buffers
INFO: start_stream(): (line:788) Camera video streaming on …
v4l2_buf.index is 0
v4l2_buf.index is 1
v4l2_buf.index is 2
v4l2_buf.index is 3
v4l2_buf.index is 4
v4l2_buf.index is 5
[ERROR] (NvV4l2ElementPlane.cpp:920) Capture Plane:Timed out waiting for dqthread
[ERROR] (NvV4l2ElementPlane.cpp:256) Output Plane:Error while Qing buffer: Device or resource busy
[ERROR] (NvV4l2ElementPlane.cpp:920) Capture Plane:Timed out waiting for dqthread
INFO: stop_stream(): (line:1041) Camera video streaming off …
[ERROR] (NvV4l2ElementPlane.cpp:178) Capture Plane:Error while DQing buffer: Broken pipe
[ERROR] (NvV4l2ElementPlane.cpp:178) Capture Plane:Error while DQing buffer: Broken pipe
[ERROR] (NvV4l2ElementPlane.cpp:256) Capture Plane:Error while Qing buffer: Device or resource busy
encoder_capture_plane_dq_callback Error while Qing buffer at capture plane
App run was successful

/*

  • Copyright (c) 2016-2019, NVIDIA CORPORATION. All rights reserved.
  • Redistribution and use in source and binary forms, with or without
  • modification, are permitted provided that the following conditions
  • are met:
    • Redistributions of source code must retain the above copyright
  • notice, this list of conditions and the following disclaimer.
    • Redistributions in binary form must reproduce the above copyright
  • notice, this list of conditions and the following disclaimer in the
  • documentation and/or other materials provided with the distribution.
    • Neither the name of NVIDIA CORPORATION nor the names of its
  • contributors may be used to endorse or promote products derived
  • from this software without specific prior written permission.
  • THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ``AS IS’’ AND ANY
  • EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
  • IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
  • PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
  • CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
  • EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
  • PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
  • PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
  • OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
  • (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
  • OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
    */

#include <stdio.h>
#include <unistd.h>
#include <sys/ioctl.h>
#include <sys/stat.h>
#include <sys/mman.h>
#include <fcntl.h>
#include <errno.h>
#include <stdlib.h>
#include <signal.h>
#include <poll.h>
#include <opencv2/opencv.hpp>

#include<fcntl.h>
#include<termios.h>

using namespace std;
using namespace cv;

#include “NvEglRenderer.h”
#include “NvUtils.h”
#include “NvCudaProc.h”
#include “nvbuf_utils.h”

#include “camera_v4l2_cuda.h”

#define MJPEG_EOS_SEARCH_SIZE 4096
#define ENABLE_GL_DISPLAY 1
//#define ENABLE_GPU_UPLOAD 1

static bool quit = false;

using namespace std;

static void
print_usage(void)
{
printf(“\n\tUsage: camera_v4l2_cuda [OPTIONS]\n\n”
“\tExample: \n”
“\t./camera_v4l2_cuda -d /dev/video0 -s 640x480 -f YUYV -n 30 -c\n\n”
“\tSupported options:\n”
“\t-d\t\tSet V4l2 video device node\n”
“\t-s\t\tSet output resolution of video device\n”
“\t-f\t\tSet output pixel format of video device (supports only YUYV/YVYU/UYVY/VYUY/GREY/MJPEG)\n”
“\t-r\t\tSet renderer frame rate (30 fps by default)\n”
“\t-n\t\tSave the n-th frame before VIC processing\n”
“\t-c\t\tEnable CUDA aglorithm (draw a black box in the upper left corner)\n”
“\t-v\t\tEnable verbose message\n”
“\t-h\t\tPrint this usage\n\n”
“\tNOTE: It runs infinitely until you terminate it with <ctrl+c>\n”);
}

static bool
parse_cmdline(context_t * ctx, int argc, char **argv)
{
int c;

if (argc < 2)
{
    print_usage();
    exit(EXIT_SUCCESS);
}

while ((c = getopt(argc, argv, "d:s:f:r:n:cvh")) != -1)
{
    switch (c)
    {
        case 'd':
            ctx->cam_devname = optarg;
            break;
        case 's':
            if (sscanf(optarg, "%dx%d",
                        &ctx->cam_w, &ctx->cam_h) != 2)
            {
                print_usage();
                return false;
            }
            break;
        case 'f':
            if (strcmp(optarg, "YUYV") == 0)
                ctx->cam_pixfmt = V4L2_PIX_FMT_YUYV;
            else if (strcmp(optarg, "YVYU") == 0)
                ctx->cam_pixfmt = V4L2_PIX_FMT_YVYU;
            else if (strcmp(optarg, "VYUY") == 0)
                ctx->cam_pixfmt = V4L2_PIX_FMT_VYUY;
            else if (strcmp(optarg, "UYVY") == 0)
                ctx->cam_pixfmt = V4L2_PIX_FMT_UYVY;
            else if (strcmp(optarg, "GREY") == 0)
                ctx->cam_pixfmt = V4L2_PIX_FMT_GREY;
            else if (strcmp(optarg, "MJPEG") == 0)
                ctx->cam_pixfmt = V4L2_PIX_FMT_MJPEG;
            else
            {
                print_usage();
                return false;
            }
            sprintf(ctx->cam_file, "camera.%s", optarg);
            break;
        case 'r':
            ctx->fps = strtol(optarg, NULL, 10);
            break;
        case 'n':
            ctx->save_n_frame = strtol(optarg, NULL, 10);
            break;
        case 'c':
            ctx->enable_cuda = true;
            break;
        case 'v':
            ctx->enable_verbose = true;
            break;
        case 'h':
            print_usage();
            exit(EXIT_SUCCESS);
            break;
        default:
            print_usage();
            return false;
    }
}

return true;

}

// roi

int ix, iy; // start of x, y
int iix, iiy; // end of x, y in move
int ttx, tty; // end of x, y

int tx, ty; // start of x, y for next draw

bool tempFlag = false;
bool drawing = false;
int select_roi = 0;
int exit_main = 0;

void on_mouse_event(int event, int x, int y, int flags, void* param)
{

switch (event)
{

	case EVENT_LBUTTONDOWN:			

		tempFlag = true;
		drawing = true;
		ix = x;
		iy = y;
		//cerr <<"EVENT_LBUTTONDOWN"<<endl;
		select_roi = 0;
		break;
		
	case EVENT_LBUTTONUP:

		tempFlag = false;
		drawing = false;
		iix = x;
		iiy = y;
		tx = ix;
		ty = iy;
		ttx = iix;
		tty = iiy;
		
		//cerr <<"EVENT_LBUTTONUP"<<endl;
		break;
		
	case EVENT_MOUSEMOVE:		
		tempFlag = false; 
		iix = x;
		iiy = y;			 
		//cerr <<"EVENT_MOUSEMOVE"<<endl;
		break;
	case EVENT_RBUTTONDOWN:
		exit_main = 1;
		quit = true;
		break;

	}

}

int SelectTargtPOS_X=0;
int SelectTargtPOS_Y=0;
int SelectTargtPOS_x_end=0;
int SelectTargtPOS_y_end=0;

void draw_roi(Mat grayimage){

if (select_roi == 0){		
										
		if (tempFlag == false && drawing == true)
			rectangle(grayimage, Point(ix, iy), Point(iix, iiy), Scalar(255,255,255),2,8,0);  // draw the rect when moving 

		if (tempFlag == false && drawing == false){
			//rectangle(frame, Point(tx, ty), Point(ttx, tty),  Scalar(255,255,255),2,8,0);  // draw the rect ROI


			int start_x = ttx > tx ?tx:ttx;
			int start_y = tty > ty ?ty:tty;

			int end_x = ttx > tx ?ttx:tx;
			int end_y = tty > ty ?tty:ty;
			
			

			Rect area(start_x, start_y, end_x - start_x , end_y - start_y );

			if ((end_x - start_x) > 0 &&  (end_y - start_y) > 0 &&  start_x >= 0 &&  start_y >= 0 && end_x > 0 && end_y > 0)
			{
				  select_roi = 1;	
				 //cout <<start_x << " " << start_y << " "<< end_x << " " << end_y<< endl;
						
				 SelectTargtPOS_X = start_x;
				 SelectTargtPOS_Y = start_y;
				 SelectTargtPOS_x_end = end_x;
				 SelectTargtPOS_y_end = end_y;	
								
					 rectangle(grayimage, Point(start_x, start_y), Point(end_x, end_y),  Scalar(255,255,255),2,8,0);  // draw the rect ROI
			}
			
			/*
				Mat img_region = frame(area);
				if ((end_x - start_x) != 0 && (end_y - start_y) != 0)
					imshow("crop", img_region);
			*/

			
	   }
   }

else if (select_roi == 1)

{	
	/* here customer need to tell the new track Rect info so we can draw again */
	rectangle(grayimage, Point(SelectTargtPOS_X, SelectTargtPOS_Y), Point(SelectTargtPOS_x_end, SelectTargtPOS_y_end), Scalar(255, 0, 255),2,8,0);
  	putText(grayimage, "Tracking", cv::Point(100, 75), FONT_HERSHEY_SIMPLEX, 2, cv::Scalar(0, 255, 0), 2, 8, 0);
	
		
}

}

// uart

char buff[64] = {0};
void* read_uart_thread_func(void* arg)
{

uint32_t count      = 0;
int      fd         = *((int*) arg);
int      ret;

fd_set fds;
FD_ZERO(&fds);
FD_SET(fd, &fds);

while (1)
{
    ret = select(fd + 1, &fds, NULL, NULL, NULL);
    if (ret <= 0)
    {
        continue;
    }
    ret = read(fd, buff, 30);
    if (ret > 0)
    {
        count++;
		buff[ret+1] = '\0';  
        printf("[got %4d bytes]:%s\n", ret, buff);

	}
    else
    {
        printf("read error\n");
    }

	if (exit_main)
		break;
}

return arg;

}

#define uart_name “/dev/ttyTHS1”
//uart_name = ‘/dev/ttyTHS2’
//uart_name = ‘/dev/ttyTHS3’
//uart_name = ‘/dev/ttyS0’

int uart_init_and_open()
{
int serial_port = open(uart_name, O_RDWR);
if (serial_port < 0){
cout << "error when open "<< uart_name << endl;
return -1;
} else

  cout << " open "<< uart_name <<  " OK "<< endl;
struct termios tty;
memset(&tty, 0, sizeof tty);


// Read in existing settings, and handle any error
if(tcgetattr(serial_port, &tty) != 0) {
	printf("Error %i from tcgetattr: %s\n", errno, strerror(errno));
	return -1;
}

tty.c_cflag |= PARENB; // Clear parity bit, disabling parity (most common)
tty.c_cflag &= ~CSTOPB; // Clear stop field, only one stop bit used in communication (most common)
tty.c_cflag |= CS8; // 8 bits per byte (most common)
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control (most common)
tty.c_cflag |= CREAD | CLOCAL; // Turn on READ & ignore ctrl lines (CLOCAL = 1)

tty.c_lflag &= ~ICANON;
tty.c_lflag &= ~ECHO; // Disable echo
tty.c_lflag &= ~ECHOE; // Disable erasure
tty.c_lflag &= ~ECHONL; // Disable new-line echo
tty.c_lflag &= ~ISIG; // Disable interpretation of INTR, QUIT and SUSP
tty.c_iflag &= ~(IXON | IXOFF | IXANY); // Turn off s/w flow ctrl
tty.c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL); // Disable any special handling of received bytes

tty.c_oflag &= ~OPOST; // Prevent special interpretation of output bytes (e.g. newline chars)
tty.c_oflag &= ~ONLCR; // Prevent conversion of newline to carriage return/line feed
// tty.c_oflag &= ~OXTABS; // Prevent conversion of tabs to spaces (NOT PRESENT ON LINUX)
// tty.c_oflag &= ~ONOEOT; // Prevent removal of C-d chars (0x004) in output (NOT PRESENT ON LINUX)

tty.c_cc[VTIME] = 10;    // Wait for up to 1s (10 deciseconds), returning as soon as any data is received.
tty.c_cc[VMIN] = 0;

// Set in/out baud rate to be 115200
cfsetispeed(&tty, B115200);
cfsetospeed(&tty, B115200);

// Save tty settings, also checking for error
if (tcsetattr(serial_port, TCSANOW, &tty) != 0) {
	printf("Error %i from tcsetattr: %s\n", errno, strerror(errno));
	return -2;
}

return serial_port;

}

int uart_send_packet(int uart_fd, char buf, char len, char crc)
{

char head[]={0xaa, 0x55, 0xaa};
int ret = 0;
ret += write(uart_fd, head, 3);
ret += write(uart_fd, &len, 1);
ret += write(uart_fd, buf, sizeof(buf));
ret += write(uart_fd, &crc, 1);

return ret;

}

// video recorder

#define TEST_ERROR(cond, str, label) if(cond) {
cerr << str << endl;
error = 1;
goto label; }

static void
abort(context_t *ctx)
{
ctx->got_error = true;
ctx->enc->abort();
}

static int
write_encoder_output_frame(ofstream * stream, NvBuffer * buffer)
{
stream->write((char *) buffer->planes[0].data, buffer->planes[0].bytesused);
return 0;
}

/**

  • Callback function called after capture plane dqbuffer of NvVideoEncoder class.

  • See NvV4l2ElementPlane::dqThread() in sample/common/class/NvV4l2ElementPlane.cpp

  • for details.

  • @param v4l2_buf : dequeued v4l2 buffer

  • @param buffer : NvBuffer associated with the dequeued v4l2 buffer

  • @param shared_buffer : Shared NvBuffer if the queued buffer is shared with

  •                     other elements. Can be NULL.
    
  • @param arg : private data set by NvV4l2ElementPlane::startDQThread()

  • @return : true for success, false for failure (will stop DQThread)
    */
    static bool
    encoder_capture_plane_dq_callback(struct v4l2_buffer *v4l2_buf, NvBuffer * buffer,
    NvBuffer * shared_buffer, void *arg)
    {
    context_t *ctx = (context_t *) arg;
    NvVideoEncoder *enc = ctx->enc;

    if (!v4l2_buf)
    {
    cerr << “Failed to dequeue buffer from encoder capture plane” << endl;
    abort(ctx);
    return false;
    }

    write_encoder_output_frame(ctx->out_file, buffer);

    /* qBuffer on the capture plane */
    if (enc->capture_plane.qBuffer(*v4l2_buf, NULL) < 0)
    {
    cerr << “encoder_capture_plane_dq_callback Error while Qing buffer at capture plane” << endl;
    abort(ctx);
    return false;
    }

    /* GOT EOS from encoder. Stop dqthread. */
    if (buffer->planes[0].bytesused == 0)
    {
    return false;
    }

    return true;
    }

static void
set_defaults_encoder(context_t * ctx)
{
memset(ctx, 0, sizeof(context_t));

ctx->bitrate = 4 * 1024 * 1024;
ctx->fps_n = 30;
ctx->fps_d = 1;
ctx->encoder_pixfmt = V4L2_PIX_FMT_H264;
ctx->out_file_path = "out.mp4";
ctx->width = 1920;
ctx->height = 1080;	

}

static void
set_defaults(context_t * ctx)
{
//memset(ctx, 0, sizeof(context_t));

ctx->cam_devname = "/dev/video0";
ctx->cam_fd = -1;
ctx->cam_pixfmt = V4L2_PIX_FMT_YUYV;
ctx->cam_w = 1920;
ctx->cam_h = 1080;
ctx->frame = 0;
ctx->save_n_frame = 0;

ctx->g_buff = NULL;
ctx->capture_dmabuf = true;
ctx->renderer = NULL;
ctx->fps = 30;

ctx->enable_cuda = false;
ctx->egl_image = NULL;
ctx->egl_display = EGL_NO_DISPLAY;

ctx->enable_verbose = true;

}

static nv_color_fmt nvcolor_fmt =
{
/* TODO: add more pixel format mapping */
{V4L2_PIX_FMT_UYVY, NvBufferColorFormat_UYVY},
{V4L2_PIX_FMT_VYUY, NvBufferColorFormat_VYUY},
{V4L2_PIX_FMT_YUYV, NvBufferColorFormat_YUYV},
{V4L2_PIX_FMT_YVYU, NvBufferColorFormat_YVYU},
{V4L2_PIX_FMT_GREY, NvBufferColorFormat_GRAY8},
{V4L2_PIX_FMT_YUV420M, NvBufferColorFormat_YUV420},
};

static NvBufferColorFormat
get_nvbuff_color_fmt(unsigned int v4l2_pixfmt)
{
unsigned i;

for (i = 0; i < sizeof(nvcolor_fmt) / sizeof(nvcolor_fmt[0]); i++)
{
    if (v4l2_pixfmt == nvcolor_fmt[i].v4l2_pixfmt)
        return nvcolor_fmt[i].nvbuff_color;
}

return NvBufferColorFormat_Invalid;

}

static bool
save_frame_to_file(context_t * ctx, struct v4l2_buffer * buf)
{
int file;

file = open(ctx->cam_file, O_CREAT | O_WRONLY | O_APPEND | O_TRUNC,
        S_IRUSR | S_IWUSR | S_IRGRP | S_IWGRP | S_IROTH | S_IWOTH);

if (-1 == file)
    ERROR_RETURN("Failed to open file for frame saving");

if (-1 == write(file, ctx->g_buff[buf->index].start,
            ctx->g_buff[buf->index].size))
{
    close(file);
    ERROR_RETURN("Failed to write frame into file");
}

close(file);

return true;

}

static bool
camera_initialize(context_t * ctx)
{
struct v4l2_format fmt;

/* Open camera device */
ctx->cam_fd = open(ctx->cam_devname, O_RDWR);
if (ctx->cam_fd == -1)
    ERROR_RETURN("Failed to open camera device %s: %s (%d)",
            ctx->cam_devname, strerror(errno), errno);

/* Set camera output format */
memset(&fmt, 0, sizeof(fmt));
fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
fmt.fmt.pix.width = ctx->cam_w;
fmt.fmt.pix.height = ctx->cam_h;
fmt.fmt.pix.pixelformat = ctx->cam_pixfmt;
fmt.fmt.pix.field = V4L2_FIELD_INTERLACED;
if (ioctl(ctx->cam_fd, VIDIOC_S_FMT, &fmt) < 0)
    ERROR_RETURN("Failed to set camera output format: %s (%d)",
            strerror(errno), errno);

/* Get the real format in case the desired is not supported */
memset(&fmt, 0, sizeof fmt);
fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
if (ioctl(ctx->cam_fd, VIDIOC_G_FMT, &fmt) < 0)
    ERROR_RETURN("Failed to get camera output format: %s (%d)",
            strerror(errno), errno);
if (fmt.fmt.pix.width != ctx->cam_w ||
        fmt.fmt.pix.height != ctx->cam_h ||
        fmt.fmt.pix.pixelformat != ctx->cam_pixfmt)
{
    WARN("The desired format is not supported");
    ctx->cam_w = fmt.fmt.pix.width;
    ctx->cam_h = fmt.fmt.pix.height;
    ctx->cam_pixfmt =fmt.fmt.pix.pixelformat;
}

struct v4l2_streamparm streamparm;
memset (&streamparm, 0x00, sizeof (struct v4l2_streamparm));
streamparm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
ioctl (ctx->cam_fd, VIDIOC_G_PARM, &streamparm);

INFO("Camera ouput format: (%d x %d)  stride: %d, imagesize: %d, frate: %u / %u",
        fmt.fmt.pix.width,
        fmt.fmt.pix.height,
        fmt.fmt.pix.bytesperline,
        fmt.fmt.pix.sizeimage,
        streamparm.parm.capture.timeperframe.denominator,
        streamparm.parm.capture.timeperframe.numerator);

return true;

}

static bool
init_components(context_t * ctx)
{
if (!camera_initialize(ctx))
ERROR_RETURN(“Failed to initialize camera device”);

INFO("Initialize v4l2 components successfully");
return true;

}

static bool
request_camera_buff(context_t ctx)
{
/
Request camera v4l2 buffer */
struct v4l2_requestbuffers rb;
memset(&rb, 0, sizeof(rb));
rb.count = V4L2_BUFFERS_NUM;
rb.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
rb.memory = V4L2_MEMORY_DMABUF;
if (ioctl(ctx->cam_fd, VIDIOC_REQBUFS, &rb) < 0)
ERROR_RETURN(“Failed to request v4l2 buffers: %s (%d)”,
strerror(errno), errno);
if (rb.count != V4L2_BUFFERS_NUM)
ERROR_RETURN(“V4l2 buffer number is not as desired”);

for (unsigned int index = 0; index < V4L2_BUFFERS_NUM; index++)
{
    struct v4l2_buffer buf;

    /* Query camera v4l2 buf length */
    memset(&buf, 0, sizeof buf);
    buf.index = index;
    buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
    buf.memory = V4L2_MEMORY_DMABUF;

    if (ioctl(ctx->cam_fd, VIDIOC_QUERYBUF, &buf) < 0)
        ERROR_RETURN("Failed to query buff: %s (%d)",
                strerror(errno), errno);

    /* TODO: add support for multi-planer
       Enqueue empty v4l2 buff into camera capture plane */
    buf.m.fd = (unsigned long)ctx->g_buff[index].dmabuff_fd;
    if (buf.length != ctx->g_buff[index].size)
    {
        WARN("Camera v4l2 buf length is not expected");
        ctx->g_buff[index].size = buf.length;
    }

    if (ioctl(ctx->cam_fd, VIDIOC_QBUF, &buf) < 0)
        ERROR_RETURN("Failed to enqueue buffers: %s (%d)",
                strerror(errno), errno);
}

return true;

}

static bool
request_camera_buff_mmap(context_t ctx)
{
/
Request camera v4l2 buffer */
struct v4l2_requestbuffers rb;
memset(&rb, 0, sizeof(rb));
rb.count = V4L2_BUFFERS_NUM;
rb.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
rb.memory = V4L2_MEMORY_MMAP;
if (ioctl(ctx->cam_fd, VIDIOC_REQBUFS, &rb) < 0)
ERROR_RETURN(“Failed to request v4l2 buffers: %s (%d)”,
strerror(errno), errno);
if (rb.count != V4L2_BUFFERS_NUM)
ERROR_RETURN(“V4l2 buffer number is not as desired”);

for (unsigned int index = 0; index < V4L2_BUFFERS_NUM; index++)
{
    struct v4l2_buffer buf;

    /* Query camera v4l2 buf length */
    memset(&buf, 0, sizeof buf);
    buf.index = index;
    buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;

    buf.memory = V4L2_MEMORY_MMAP;
    if (ioctl(ctx->cam_fd, VIDIOC_QUERYBUF, &buf) < 0)
        ERROR_RETURN("Failed to query buff: %s (%d)",
                strerror(errno), errno);

    ctx->g_buff[index].size = buf.length;
    ctx->g_buff[index].start = (unsigned char *)
        mmap (NULL /* start anywhere */,
                buf.length,
                PROT_READ | PROT_WRITE /* required */,
                MAP_SHARED /* recommended */,
                ctx->cam_fd, buf.m.offset);
    if (MAP_FAILED == ctx->g_buff[index].start)
        ERROR_RETURN("Failed to map buffers");

    if (ioctl(ctx->cam_fd, VIDIOC_QBUF, &buf) < 0)
        ERROR_RETURN("Failed to enqueue buffers: %s (%d)",
                strerror(errno), errno);
}

return true;

}

static bool
prepare_buffers(context_t * ctx)
{
NvBufferCreateParams input_params = {0};

/* Allocate global buffer context */
ctx->g_buff = (nv_buffer *)malloc(V4L2_BUFFERS_NUM * sizeof(nv_buffer));
if (ctx->g_buff == NULL)
    ERROR_RETURN("Failed to allocate global buffer context");

input_params.payloadType = NvBufferPayload_SurfArray;
input_params.width = ctx->cam_w;
input_params.height = ctx->cam_h;
input_params.layout = NvBufferLayout_Pitch;

/* Create buffer and provide it with camera */
for (unsigned int index = 0; index < V4L2_BUFFERS_NUM; index++)
{
    int fd;
    NvBufferParams params = {0};

    input_params.colorFormat = get_nvbuff_color_fmt(ctx->cam_pixfmt);
    input_params.nvbuf_tag = NvBufferTag_CAMERA;
    if (-1 == NvBufferCreateEx(&fd, &input_params))
        ERROR_RETURN("Failed to create NvBuffer");

    ctx->g_buff[index].dmabuff_fd = fd;

    if (-1 == NvBufferGetParams(fd, &params))
        ERROR_RETURN("Failed to get NvBuffer parameters");


    /* TODO: add multi-planar support
       Currently only supports YUV422 interlaced single-planar */
    if (ctx->capture_dmabuf) {
        if (-1 == NvBufferMemMap(ctx->g_buff[index].dmabuff_fd, 0, NvBufferMem_Read_Write,
                    (void**)&ctx->g_buff[index].start))
            ERROR_RETURN("Failed to map buffer");
    }
}

input_params.colorFormat = get_nvbuff_color_fmt(V4L2_PIX_FMT_YUV420M);
input_params.nvbuf_tag = NvBufferTag_NONE;
/* Create Render buffer */
if (-1 == NvBufferCreateEx(&ctx->render_dmabuf_fd, &input_params))
    ERROR_RETURN("Failed to create NvBuffer");

if (ctx->capture_dmabuf) {
    if (!request_camera_buff(ctx))
        ERROR_RETURN("Failed to set up camera buff");
} else {
    if (!request_camera_buff_mmap(ctx))
        ERROR_RETURN("Failed to set up camera buff");
}

INFO("Succeed in preparing stream buffers");
return true;

}

static bool
start_stream(context_t * ctx)
{
enum v4l2_buf_type type;

/* Start v4l2 streaming */
type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
if (ioctl(ctx->cam_fd, VIDIOC_STREAMON, &type) < 0)
    ERROR_RETURN("Failed to start streaming: %s (%d)",
            strerror(errno), errno);

usleep(200);

INFO("Camera video streaming on ...");
return true;

}

static void
signal_handle(int signum)
{
printf(“Quit due to exit command from user!\n”);
quit = true;
}

int encode_frame(int fd)
{

}

#define MAX_QUEUED_BUFFERS (6)

int rec_count = 0;

static int
read_yuv420_fake_frame(NvBuffer & buffer)
{
uint32_t i, j;
char *data;

for (i = 0; i < buffer.n_planes; i++)
{
    NvBuffer::NvBufferPlane &plane = buffer.planes[i];
    std::streamsize bytes_to_read =
        plane.fmt.bytesperpixel * plane.fmt.width;
    data = (char *) plane.data;
	//cout << buffer.n_planes << " "<< plane.fmt.bytesperpixel << " " << plane.fmt.width << plane.fmt.height << endl;
    plane.bytesused = 0;
    for (j = 0; j < plane.fmt.height; j++)
    {
        memset(data, 0xaa, bytes_to_read);
        data += plane.fmt.stride;
    }
    plane.bytesused = plane.fmt.stride * plane.fmt.height;
}
return 0;

}

static int encode_yuv(context_t *ctx)
{
struct v4l2_buffer v4l2_buf;
struct v4l2_plane planes[MAX_PLANES];
int ret = 0;

memset(&v4l2_buf, 0, sizeof(v4l2_buf));
memset(planes, 0, MAX_PLANES * sizeof(struct v4l2_plane));
v4l2_buf.m.planes = planes;
if (ctx->enc->output_plane.getNumQueuedBuffers() < MAX_QUEUED_BUFFERS)
{
    v4l2_buf.index = ctx->enc->output_plane.getNumQueuedBuffers();
	cout << "v4l2_buf.index is " << v4l2_buf.index << endl;
	NvBuffer *buffer = ctx->enc->output_plane.getNthBuffer(v4l2_buf.index);
    read_yuv420_fake_frame(*buffer);
	v4l2_buf.m.planes[0].bytesused = buffer->planes[0].bytesused;
	v4l2_buf.m.planes[1].bytesused = buffer->planes[1].bytesused;
	v4l2_buf.m.planes[2].bytesused = buffer->planes[2].bytesused;
	//cout << v4l2_buf.m.planes[0].bytesused << endl;
    ret = ctx->enc->output_plane.qBuffer(v4l2_buf, NULL);
	if (ret < 0)
		abort(ctx);
}
else
{
	
	NvBuffer *buffer;
    ret = ctx->enc->output_plane.dqBuffer(v4l2_buf, &buffer, NULL, 10);
	if (ret < 0)
		abort(ctx);

	if (read_yuv420_fake_frame(*buffer) < 0)
    {
        cerr << "Could not read complete frame from input file" << endl;
        v4l2_buf.m.planes[0].bytesused = 0;
    }
	
    ret = ctx->enc->output_plane.qBuffer(v4l2_buf, NULL);
	if (ret < 0)
		abort(ctx);
	
}

return true;

}

void helper_get_cam_frame(unsigned char **pointer_to_cam_data, context_t * ctx, int index)
{
pointer_to_cam_data = (unsigned char) ctx->g_buff[index].start;
}

static bool
start_capture(context_t * ctx)
{
struct sigaction sig_action;
int ret = -1;
struct pollfd fds[1];
NvBufferTransformParams transParams;

/* Register a shuwdown handler to ensure
   a clean shutdown if user types <ctrl+c> */
sig_action.sa_handler = signal_handle;
sigemptyset(&sig_action.sa_mask);
sig_action.sa_flags = 0;
sigaction(SIGINT, &sig_action, NULL);

/* Init the NvBufferTransformParams */
memset(&transParams, 0, sizeof(transParams));
transParams.transform_flag = NVBUFFER_TRANSFORM_FILTER;
transParams.transform_filter = NvBufferTransform_Filter_Smart;


fds[0].fd = ctx->cam_fd;
fds[0].events = POLLIN;
/* Wait for camera event with timeout = 5000 ms */
Mat yuyv_frame  = Mat(ctx->cam_h, ctx->cam_w, CV_8UC2);
Mat preview;
unsigned char* ptr_cam_frame;
	int start_clock_in_us = 0;

#if (defined ENABLE_GL_DISPLAY) && (defined ENABLE_GPU_UPLOAD)
 cuda::GpuMat gpu_frame;
#endif
	
while (poll(fds, 1, 10000) > 0)
{
    if (fds[0].revents & POLLIN) {
		start_clock_in_us = clock();
        struct v4l2_buffer v4l2_buf;

        /* Dequeue a camera buff */
        memset(&v4l2_buf, 0, sizeof(v4l2_buf));
        v4l2_buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
        if (ctx->capture_dmabuf)
            v4l2_buf.memory = V4L2_MEMORY_DMABUF;
        else
            v4l2_buf.memory = V4L2_MEMORY_MMAP;
        if (ioctl(ctx->cam_fd, VIDIOC_DQBUF, &v4l2_buf) < 0)
            ERROR_RETURN("Failed to dequeue camera buff: %s (%d)",
                    strerror(errno), errno);

        ctx->frame++;

        /* Save the n-th frame to file */
        //if (ctx->frame == ctx->save_n_frame)
        //    save_frame_to_file(ctx, &v4l2_buf);

    
        if (ctx->capture_dmabuf) {
            /* Cache sync for VIC operation since the data is from CPU */
           NvBufferMemSyncForDevice(ctx->g_buff[v4l2_buf.index].dmabuff_fd, 0,
                    (void**)&ctx->g_buff[v4l2_buf.index].start);
        } else {
            /* Copies raw buffer plane contents to an NvBuffer plane */
            Raw2NvBuffer(ctx->g_buff[v4l2_buf.index].start, 0,
                    ctx->cam_w, ctx->cam_h, ctx->g_buff[v4l2_buf.index].dmabuff_fd);
        }

        /*  Convert the camera buffer from YUV422 to YUV420P */
        if (-1 == NvBufferTransform(ctx->g_buff[v4l2_buf.index].dmabuff_fd, ctx->render_dmabuf_fd,
                    &transParams))
            ERROR_RETURN("Failed to convert the buffer");
		
		helper_get_cam_frame(&ptr_cam_frame, ctx, v4l2_buf.index);
		yuyv_frame.data = ptr_cam_frame;			

		if(yuyv_frame.empty()) {
			cout << "Img load failed" << endl;
		}else
		{
		
	    	//cvtColor(yuyv_frame, preview, COLOR_YUV2BGR_UYVY);
			cvtColor(yuyv_frame, preview, COLOR_YUV2GRAY_UYVY);				
			draw_roi(preview);	
			putText(preview, buff, cv::Point(200, 200), FONT_HERSHEY_SIMPLEX, 2, cv::Scalar(0, 255, 0), 2, 8, 0);
			#if (defined ENABLE_GL_DISPLAY) && (defined ENABLE_GPU_UPLOAD)
				gpu_frame.upload(preview);
				imshow("test", gpu_frame);
			#else
				imshow("test", preview);
			#endif
		}

		
		if (waitKey(1) == 27) {   // ESC 
			break;
		}

		encode_yuv(ctx);
			
		if(quit){
		   	break;
		}
		
        /* Enqueue camera buffer back to driver */
        if (ioctl(ctx->cam_fd, VIDIOC_QBUF, &v4l2_buf))
            ERROR_RETURN("Failed to queue camera buffers: %s (%d)",
                    strerror(errno), errno);
	
		//cout <<"frame diff " << (clock() - start_clock_in_us)/1000.0 << "ms" << endl;
    }
}

/* Print profiling information when streaming stops */

ctx->enc->capture_plane.waitForDQThread(2000);
return true;

}

static bool
stop_stream(context_t * ctx){
enum v4l2_buf_type type;

// Stop v4l2 streaming
type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
if (ioctl(ctx->cam_fd, VIDIOC_STREAMOFF, &type))
	ERROR_RETURN("Failed to stop streaming: %s (%d)",
			strerror(errno), errno);


// Send EOS to ENC output plane
{
	struct v4l2_buffer v4l2_buf;
	struct v4l2_plane planes[MAX_PLANES];

	memset(&v4l2_buf, 0, sizeof(v4l2_buf));
	memset(planes, 0, MAX_PLANES * sizeof(struct v4l2_plane));

	v4l2_buf.m.planes = planes;
	v4l2_buf.m.planes[0].m.fd = -1;
	v4l2_buf.m.planes[0].bytesused = 0;
	ctx->enc->output_plane.qBuffer(v4l2_buf, NULL);

	// Wait till capture plane DQ Thread finishes
	// i.e. all the capture plane buffers are dequeued
	ctx->enc->capture_plane.waitForDQThread(3000);
}
// Stop ENC output plane
if (ctx->enc->output_plane.setStreamStatus(false) < 0)
	ERROR_RETURN("Failed to stop output plane streaming");

// Stop ENC capture plane
if (ctx->enc->capture_plane.setStreamStatus(false) < 0)
	ERROR_RETURN("Failed to stop output plane streaming");

	INFO("Camera video streaming off ...");

    return true;

}

int
main(int argc, char *argv)
{
context_t ctx;
int error = 0;
namedWindow(“test”, WINDOW_AUTOSIZE | WINDOW_OPENGL);
//cv::startWindowThread();
//cout << cv::getBuildInformation() <<endl;
setMouseCallback(“test”, on_mouse_event);
int ret = -1;

	/* init uart and send test string */

int uart_fd = uart_init_and_open();
if (uart_fd < 0){
	cout << " open uart failed " << endl;
	cout << " please run it with sudo " << endl;		
	exit(-1);	
}

write(uart_fd, "Hello, world!\n", sizeof("Hello, world!\n"));

char test_buf[] = {0,0,0,0,0,0,0,0,0,0,0,0};
uart_send_packet(uart_fd, test_buf, sizeof(test_buf), 1);

pthread_t read_thread;
pthread_create(&read_thread, NULL, read_uart_thread_func, (void*) &uart_fd);



//encoder 
set_defaults_encoder(&ctx);

ctx.out_file = new ofstream(ctx.out_file_path);
TEST_ERROR(!ctx.out_file->is_open(), "Could not open output file", cleanup);

ctx.enc = NvVideoEncoder::createVideoEncoder("enc0");
TEST_ERROR(!ctx.enc, "Could not create encoder", cleanup);


/**
	* It is necessary that Capture Plane format be set before Output Plane
	* format.
	* It is necessary to set width and height on the capture plane as well.
	*/
   ret =
	   ctx.enc->setCapturePlaneFormat(ctx.encoder_pixfmt, ctx.width,
									 ctx.height, 4 * 1024 * 1024);
   TEST_ERROR(ret < 0, "Could not set capture plane format", cleanup);

   ret =
	   ctx.enc->setOutputPlaneFormat(V4L2_PIX_FMT_YUV420M, ctx.width,
									 ctx.height);
   TEST_ERROR(ret < 0, "Could not set output plane format", cleanup);

   ret = ctx.enc->setBitrate(ctx.bitrate);
   TEST_ERROR(ret < 0, "Could not set bitrate", cleanup);

   if (ctx.encoder_pixfmt == V4L2_PIX_FMT_H264)
   {
	   ret = ctx.enc->setProfile(V4L2_MPEG_VIDEO_H264_PROFILE_HIGH);
   }

   TEST_ERROR(ret < 0, "Could not set encoder profile", cleanup);

   if (ctx.encoder_pixfmt == V4L2_PIX_FMT_H264)
   {
	   ret = ctx.enc->setLevel(V4L2_MPEG_VIDEO_H264_LEVEL_5_0);
	   TEST_ERROR(ret < 0, "Could not set encoder level", cleanup);
   }

   ret = ctx.enc->setFrameRate(ctx.fps_n, ctx.fps_d);
   TEST_ERROR(ret < 0, "Could not set framerate", cleanup);

   /**
	* Query, Export and Map the output plane buffers so that we can read
	* raw data into the buffers
	*/
   ret = ctx.enc->output_plane.setupPlane(V4L2_MEMORY_MMAP, 6, true, false);
   TEST_ERROR(ret < 0, "Could not setup output plane", cleanup);

   /**
	* Query, Export and Map the capture plane buffers so that we can write
	* encoded data from the buffers
	*/
   ret = ctx.enc->capture_plane.setupPlane(V4L2_MEMORY_MMAP, 6, true, false);
   TEST_ERROR(ret < 0, "Could not setup capture plane", cleanup);

   /* output plane STREAMON */
   ret = ctx.enc->output_plane.setStreamStatus(true);
   TEST_ERROR(ret < 0, "Error in output plane streamon", cleanup);

   /* capture plane STREAMON */
   ret = ctx.enc->capture_plane.setStreamStatus(true);
   TEST_ERROR(ret < 0, "Error in capture plane streamon", cleanup);

   ctx.enc->capture_plane.
	   setDQThreadCallback(encoder_capture_plane_dq_callback);

   /**
	* startDQThread starts a thread internally which calls the
	* encoder_capture_plane_dq_callback whenever a buffer is dequeued
	* on the plane
	*/
   ctx.enc->capture_plane.startDQThread(&ctx);
	
/* Enqueue all the empty capture plane buffers */
	for (uint32_t i = 0; i < ctx.enc->capture_plane.getNumBuffers(); i++)
	{
		struct v4l2_buffer v4l2_buf;
		struct v4l2_plane planes[MAX_PLANES];

		memset(&v4l2_buf, 0, sizeof(v4l2_buf));
		memset(planes, 0, MAX_PLANES * sizeof(struct v4l2_plane));

		v4l2_buf.index = i;
		v4l2_buf.m.planes = planes;
		cout << i << endl;
		ret = ctx.enc->capture_plane.qBuffer(v4l2_buf, NULL);
		if (ret < 0)
		{
			cerr << "Error while queueing buffer at capture plane" << endl;
			abort(&ctx);
			goto cleanup;
		}
	}


// camera

set_defaults(&ctx);

CHECK_ERROR(parse_cmdline(&ctx, argc, argv), cleanup,
        "Invalid options specified");

/* Initialize camera and EGL display, EGL Display will be used to map
   the buffer to CUDA buffer for CUDA processing */
CHECK_ERROR(init_components(&ctx), cleanup,
        "Failed to initialize v4l2 components");


CHECK_ERROR(prepare_buffers(&ctx), cleanup,
        "Failed to prepare v4l2 buffs");


CHECK_ERROR(start_stream(&ctx), cleanup,
        "Failed to start streaming");

CHECK_ERROR(start_capture(&ctx), cleanup,
        "Failed to start capturing")

CHECK_ERROR(stop_stream(&ctx), cleanup,
        "Failed to stop streaming");

cleanup:
if (ctx.cam_fd > 0)
close(ctx.cam_fd);

if (ctx.renderer != NULL)
    delete ctx.renderer;

if (ctx.egl_display && !eglTerminate(ctx.egl_display))
    printf("Failed to terminate EGL display connection\n");

if (ctx.g_buff != NULL)
{
    for (unsigned i = 0; i < V4L2_BUFFERS_NUM; i++) {
        if (ctx.g_buff[i].dmabuff_fd)
            NvBufferDestroy(ctx.g_buff[i].dmabuff_fd);
        if (ctx.cam_pixfmt == V4L2_PIX_FMT_MJPEG)
            munmap(ctx.g_buff[i].start, ctx.g_buff[i].size);
    }
    free(ctx.g_buff);
}

NvBufferDestroy(ctx.render_dmabuf_fd);

if (error)
    printf("App run failed\n");
else
    printf("App run was successful\n");


delete ctx.enc;
delete ctx.out_file;
return -error;

}

camera_v4l2_cuda.cpp (34.8 KB)

Have you confirm by below command first.

v4l2-ctl --stream-mmap --stream-count=100 -d /dev/video0

send byteused 0 and to notify the capture now issue sovled

Hi,

I have the same issue but i did not understand what to do, can you post a sample?

My code:

v4l2_buf.m.planes[0].bytesused = 0;
// Wait till capture plane DQ Thread finishes
// i.e. all the capture plane buffers are dequeued
m_ImageConverter->capture_plane.waitForDQThread(2000);

Thanks.