#include <usb_cam.h>
Definition at line 62 of file usb_cam.h.
Enumerator |
---|
IO_METHOD_READ |
|
IO_METHOD_MMAP |
|
IO_METHOD_USERPTR |
|
IO_METHOD_UNKNOWN |
|
Definition at line 64 of file usb_cam.h.
Enumerator |
---|
PIXEL_FORMAT_YUYV |
|
PIXEL_FORMAT_UYVY |
|
PIXEL_FORMAT_MJPEG |
|
PIXEL_FORMAT_YUVMONO10 |
|
PIXEL_FORMAT_RGB24 |
|
PIXEL_FORMAT_GREY |
|
PIXEL_FORMAT_UNKNOWN |
|
Definition at line 69 of file usb_cam.h.
usb_cam::UsbCam::UsbCam |
( |
| ) |
|
usb_cam::UsbCam::~UsbCam |
( |
| ) |
|
void usb_cam::UsbCam::close_device |
( |
void |
| ) |
|
|
private |
void usb_cam::UsbCam::grab_image |
( |
sensor_msgs::Image * |
image | ) |
|
void usb_cam::UsbCam::grab_image |
( |
| ) |
|
|
private |
void usb_cam::UsbCam::init_device |
( |
int |
image_width, |
|
|
int |
image_height, |
|
|
int |
framerate |
|
) |
| |
|
private |
int usb_cam::UsbCam::init_mjpeg_decoder |
( |
int |
image_width, |
|
|
int |
image_height |
|
) |
| |
|
private |
void usb_cam::UsbCam::init_mmap |
( |
void |
| ) |
|
|
private |
void usb_cam::UsbCam::init_read |
( |
unsigned int |
buffer_size | ) |
|
|
private |
void usb_cam::UsbCam::init_userp |
( |
unsigned int |
buffer_size | ) |
|
|
private |
bool usb_cam::UsbCam::is_capturing |
( |
| ) |
|
void usb_cam::UsbCam::mjpeg2rgb |
( |
char * |
MJPEG, |
|
|
int |
len, |
|
|
char * |
RGB, |
|
|
int |
NumPixels |
|
) |
| |
|
private |
void usb_cam::UsbCam::open_device |
( |
void |
| ) |
|
|
private |
void usb_cam::UsbCam::process_image |
( |
const void * |
src, |
|
|
int |
len, |
|
|
camera_image_t * |
dest |
|
) |
| |
|
private |
int usb_cam::UsbCam::read_frame |
( |
| ) |
|
|
private |
void usb_cam::UsbCam::set_auto_focus |
( |
int |
value | ) |
|
void usb_cam::UsbCam::set_v4l_parameter |
( |
const std::string & |
param, |
|
|
int |
value |
|
) |
| |
Set video device parameter via call to v4l-utils.
- Parameters
-
param | The name of the parameter to set |
param | The value to assign |
Definition at line 1181 of file usb_cam.cpp.
void usb_cam::UsbCam::set_v4l_parameter |
( |
const std::string & |
param, |
|
|
const std::string & |
value |
|
) |
| |
Set video device parameter via call to v4l-utils.
- Parameters
-
param | The name of the parameter to set |
param | The value to assign |
Definition at line 1191 of file usb_cam.cpp.
void usb_cam::UsbCam::shutdown |
( |
void |
| ) |
|
void usb_cam::UsbCam::start |
( |
const std::string & |
dev, |
|
|
io_method |
io, |
|
|
pixel_format |
pf, |
|
|
int |
image_width, |
|
|
int |
image_height, |
|
|
int |
framerate |
|
) |
| |
void usb_cam::UsbCam::start_capturing |
( |
void |
| ) |
|
void usb_cam::UsbCam::stop_capturing |
( |
void |
| ) |
|
void usb_cam::UsbCam::uninit_device |
( |
void |
| ) |
|
|
private |
AVCodec* usb_cam::UsbCam::avcodec_ |
|
private |
AVCodecContext* usb_cam::UsbCam::avcodec_context_ |
|
private |
AVFrame* usb_cam::UsbCam::avframe_camera_ |
|
private |
int usb_cam::UsbCam::avframe_camera_size_ |
|
private |
AVFrame* usb_cam::UsbCam::avframe_rgb_ |
|
private |
int usb_cam::UsbCam::avframe_rgb_size_ |
|
private |
AVDictionary* usb_cam::UsbCam::avoptions_ |
|
private |
buffer* usb_cam::UsbCam::buffers_ |
|
private |
std::string usb_cam::UsbCam::camera_dev_ |
|
private |
bool usb_cam::UsbCam::is_capturing_ |
|
private |
bool usb_cam::UsbCam::monochrome_ |
|
private |
unsigned int usb_cam::UsbCam::n_buffers_ |
|
private |
unsigned int usb_cam::UsbCam::pixelformat_ |
|
private |
struct SwsContext* usb_cam::UsbCam::video_sws_ |
|
private |
The documentation for this class was generated from the following files: