mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_Linux: VideoIn: follow coding style and minor fixes
- No need to if/else if just returning - Sort includes - Fix missing space in log message - When closing the fd, set it to -1. It's better to later fail the operation than to operate on another random file descriptor - Add some spaces to improve readability - Use pragma once - Do not initialize members to zero, it's already the behavior for our custom allocator
This commit is contained in:
parent
25df4d03ff
commit
c75704bde3
@ -21,22 +21,21 @@
|
|||||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||||
#include "VideoIn.h"
|
#include "VideoIn.h"
|
||||||
|
|
||||||
#include <stdio.h>
|
|
||||||
#include <string.h>
|
|
||||||
#include <fcntl.h>
|
|
||||||
#include <unistd.h>
|
|
||||||
#include <stdlib.h>
|
|
||||||
#include <errno.h>
|
#include <errno.h>
|
||||||
#include <sched.h>
|
#include <fcntl.h>
|
||||||
#include <time.h>
|
#include <linux/videodev2.h>
|
||||||
#include <pthread.h>
|
#include <pthread.h>
|
||||||
|
#include <sched.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <string.h>
|
||||||
#include <sys/ioctl.h>
|
#include <sys/ioctl.h>
|
||||||
#include <sys/mman.h>
|
#include <sys/mman.h>
|
||||||
#include <sys/select.h>
|
#include <sys/select.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
#include <sys/time.h>
|
#include <sys/time.h>
|
||||||
|
#include <time.h>
|
||||||
#include <linux/videodev2.h>
|
#include <unistd.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -52,11 +51,7 @@ bool VideoIn::get_frame(Frame &frame)
|
|||||||
_streaming = true;
|
_streaming = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_dequeue_frame(frame)) {
|
return _dequeue_frame(frame);
|
||||||
return true;
|
|
||||||
} else {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void VideoIn::put_frame(Frame &frame)
|
void VideoIn::put_frame(Frame &frame)
|
||||||
@ -88,9 +83,10 @@ bool VideoIn::open_device(const char *device_path, uint32_t memtype)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE)) {
|
if (!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE)) {
|
||||||
hal.console->printf("Error opening device %s: is not a video capture"
|
hal.console->printf("Error opening device %s: is not a video capture device\n",
|
||||||
"device\n", device_path);
|
device_path);
|
||||||
close(_fd);
|
close(_fd);
|
||||||
|
_fd = -1;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -112,8 +108,7 @@ bool VideoIn::allocate_buffers(uint32_t nbufs)
|
|||||||
|
|
||||||
ret = ioctl(_fd, VIDIOC_REQBUFS, &rb);
|
ret = ioctl(_fd, VIDIOC_REQBUFS, &rb);
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
printf("Unable to request buffers: %s (%d).\n", strerror(errno),
|
printf("Unable to request buffers: %s (%d).\n", strerror(errno), errno);
|
||||||
errno);
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -138,7 +133,7 @@ bool VideoIn::allocate_buffers(uint32_t nbufs)
|
|||||||
switch (_memtype) {
|
switch (_memtype) {
|
||||||
case V4L2_MEMORY_MMAP:
|
case V4L2_MEMORY_MMAP:
|
||||||
buffers[i].mem = mmap(0, buf.length, PROT_READ | PROT_WRITE,
|
buffers[i].mem = mmap(0, buf.length, PROT_READ | PROT_WRITE,
|
||||||
MAP_SHARED, _fd, buf.m.offset);
|
MAP_SHARED, _fd, buf.m.offset);
|
||||||
if (buffers[i].mem == MAP_FAILED) {
|
if (buffers[i].mem == MAP_FAILED) {
|
||||||
hal.console->printf("Unable to map buffer %u: %s (%d)\n", i,
|
hal.console->printf("Unable to map buffer %u: %s (%d)\n", i,
|
||||||
strerror(errno), errno);
|
strerror(errno), errno);
|
||||||
@ -249,6 +244,7 @@ void VideoIn::_queue_buffer(int index)
|
|||||||
{
|
{
|
||||||
int ret;
|
int ret;
|
||||||
struct v4l2_buffer buf;
|
struct v4l2_buffer buf;
|
||||||
|
|
||||||
memset(&buf, 0, sizeof buf);
|
memset(&buf, 0, sizeof buf);
|
||||||
buf.index = index;
|
buf.index = index;
|
||||||
buf.type = V4L2_CAP_VIDEO_CAPTURE;
|
buf.type = V4L2_CAP_VIDEO_CAPTURE;
|
||||||
@ -257,6 +253,7 @@ void VideoIn::_queue_buffer(int index)
|
|||||||
if (_memtype == V4L2_MEMORY_USERPTR) {
|
if (_memtype == V4L2_MEMORY_USERPTR) {
|
||||||
buf.m.userptr = (unsigned long) _buffers[index].mem;
|
buf.m.userptr = (unsigned long) _buffers[index].mem;
|
||||||
}
|
}
|
||||||
|
|
||||||
ret = ioctl(_fd, VIDIOC_QBUF, &buf);
|
ret = ioctl(_fd, VIDIOC_QBUF, &buf);
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
hal.console->printf("Unable to queue buffer : %s (%d).\n",
|
hal.console->printf("Unable to queue buffer : %s (%d).\n",
|
||||||
|
@ -12,8 +12,7 @@
|
|||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
#ifndef __VIDEOIN_H__
|
#pragma once
|
||||||
#define __VIDEOIN_H__
|
|
||||||
|
|
||||||
#include "AP_HAL_Linux.h"
|
#include "AP_HAL_Linux.h"
|
||||||
#include <linux/videodev2.h>
|
#include <linux/videodev2.h>
|
||||||
@ -25,15 +24,15 @@ struct buffer {
|
|||||||
|
|
||||||
class Linux::VideoIn {
|
class Linux::VideoIn {
|
||||||
public:
|
public:
|
||||||
/* This structure implements the fields of the v4l2_pix_format struct
|
/* This structure implements the fields of the v4l2_pix_format struct
|
||||||
* that are considered useful for an optical flow application along
|
* that are considered useful for an optical flow application along
|
||||||
* with the v4l2_buffer fields timestamp and sequence*/
|
* with the v4l2_buffer fields timestamp and sequence*/
|
||||||
class Frame {
|
class Frame {
|
||||||
friend class VideoIn;
|
friend class VideoIn;
|
||||||
public:
|
public:
|
||||||
uint32_t timestamp = 0;
|
uint32_t timestamp;
|
||||||
uint32_t sequence = 0;
|
uint32_t sequence;
|
||||||
void *data = NULL;
|
void *data;
|
||||||
private:
|
private:
|
||||||
uint32_t buf_index;
|
uint32_t buf_index;
|
||||||
};
|
};
|
||||||
@ -56,14 +55,13 @@ private:
|
|||||||
bool _dequeue_frame(Frame &frame);
|
bool _dequeue_frame(Frame &frame);
|
||||||
uint32_t _timeval_to_us(struct timeval& tv);
|
uint32_t _timeval_to_us(struct timeval& tv);
|
||||||
int _fd = -1;
|
int _fd = -1;
|
||||||
struct buffer *_buffers = NULL;
|
struct buffer *_buffers;
|
||||||
unsigned int _nbufs = 0;
|
unsigned int _nbufs;
|
||||||
bool _streaming = false;
|
bool _streaming;
|
||||||
uint32_t _width = 0;
|
uint32_t _width;
|
||||||
uint32_t _height = 0;
|
uint32_t _height;
|
||||||
uint32_t _format = 0;
|
uint32_t _format;
|
||||||
uint32_t _bytesperline = 0;
|
uint32_t _bytesperline;
|
||||||
uint32_t _sizeimage = 0;
|
uint32_t _sizeimage;
|
||||||
uint32_t _memtype = V4L2_MEMORY_MMAP;
|
uint32_t _memtype = V4L2_MEMORY_MMAP;
|
||||||
};
|
};
|
||||||
#endif
|
|
||||||
|
Loading…
Reference in New Issue
Block a user