#include <usb_cam.h>

| Static Public Member Functions | |
| static UsbCam & | Instance () | 
|  Static Public Member Functions inherited from usb_cam::AbstractV4LUSBCam | |
| static std::vector< capture_format_t > & | get_supported_formats () | 
| Static Protected Member Functions | |
| static void | frame_timer_callback (const ros::TimerEvent &event) | 
| static bool | service_start_callback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response) | 
| static bool | service_stop_callback (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response) | 
| static bool | service_supported_controls_callback (std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response) | 
| static bool | service_supported_formats_callback (std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response) | 
|  Static Protected Member Functions inherited from usb_cam::AbstractV4LUSBCam | |
| static void | adjust_camera () | 
| static void | close_handlers () | 
| static bool | decode_ffmpeg (const void *src, int len, camera_image_t *dest) | 
| static bool | init () | 
| static bool | init_decoder () | 
| static bool | process_image (const void *src, int len, camera_image_t *dest) | 
| static camera_image_t * | read_frame () | 
| static void | release_device () | 
| static void | run_grabber (unsigned int &buffer_size) | 
| static bool | set_v4l_parameter (const std::string ¶m, bool value) | 
| static bool | set_v4l_parameter (const std::string ¶m, const std::string &value) | 
| static bool | set_v4l_parameter (const std::string ¶m, int value) | 
| static bool | set_v4l_parameter (const std::string ¶m, long value) | 
| static bool | start () | 
| static bool | start_capture () | 
| static bool | suspend () | 
| static void | v4l_query_controls () | 
| Protected Attributes | |
| ros::Timer | _frame_timer | 
| image_transport::CameraPublisher | _image_pub | 
| image_transport::ImageTransport | _image_transport | 
| sensor_msgs::Image | _img_msg | 
| ros::ServiceServer | _service_start | 
| std::string | _service_start_name | 
| ros::ServiceServer | _service_stop | 
| std::string | _service_stop_name | 
| ros::ServiceServer | _service_supported_controls | 
| ros::ServiceServer | _service_supported_formats | 
| ros::NodeHandle | node | 
|  Protected Attributes inherited from usb_cam::AbstractV4LUSBCam | |
| camera_image_t | _image | 
| Static Protected Attributes | |
| static std::string | camera_frame_id = "head_camera" | 
| static camera_info_manager::CameraInfoManager * | camera_info = nullptr | 
| static std::string | camera_info_url = "" | 
| static std::string | camera_name = "head_camera" | 
| static std::string | camera_transport_suffix = "image_raw" | 
| static bool | create_suspended = false | 
| static ros::Timer * | frame_timer = nullptr | 
| static image_transport::CameraPublisher * | image_pub = nullptr | 
| static image_transport::ImageTransport * | image_transport = nullptr | 
| static sensor_msgs::Image * | img_msg = nullptr | 
| static ros::ServiceServer * | service_start = nullptr | 
| static ros::ServiceServer * | service_stop = nullptr | 
| static ros::ServiceServer * | service_supported_controls = nullptr | 
| static ros::ServiceServer * | service_supported_formats = nullptr | 
|  Static Protected Attributes inherited from usb_cam::AbstractV4LUSBCam | |
| static AVCodec * | avcodec = nullptr | 
| static AVCodecContext * | avcodec_context = nullptr | 
| static AVFrame * | avframe_camera = nullptr | 
| static int | avframe_camera_size = 0 | 
| static AVFrame * | avframe_rgb = nullptr | 
| static int | avframe_rgb_size = 0 | 
| static AVDictionary * | avoptions = nullptr | 
| static AVPacket * | avpkt = nullptr | 
| static buffer * | buffers = nullptr | 
| static unsigned int | buffers_count = 0 | 
| static bool | capturing = false | 
| static AVCodecID | codec_id = AV_CODEC_ID_NONE | 
| static color_format_t | color_format = COLOR_FORMAT_UNKNOWN | 
| static std::string | color_format_name = "yuv422p" | 
| static std::vector< camera_control_t > | controls = std::vector<camera_control_t>() | 
| static const time_t | epoch_time_shift_us = util::get_epoch_time_shift_us() | 
| static int | file_dev = -1 | 
| static int | framerate = 10 | 
| static bool | full_ffmpeg_log = false | 
| static std::set< std::string > | ignore_controls = std::set<std::string>() | 
| static camera_image_t * | image = nullptr | 
| static int | image_height = 240 | 
| static int | image_width = 320 | 
| static io_method_t | io_method = io_method_t::IO_METHOD_MMAP | 
| static std::string | io_method_name = "mmap" | 
| static bool | monochrome = false | 
| static pixel_format_t | pixel_format = PIXEL_FORMAT_UNKNOWN | 
| static std::string | pixel_format_name = "uyvy" | 
| static bool | streaming_status = false | 
| static std::vector< capture_format_t > | supported_formats = std::vector<capture_format_t>() | 
| static unsigned int | v4l_pixel_format = V4L2_PIX_FMT_UYVY | 
| static std::string | video_device_name = "/dev/video0" | 
| static struct SwsContext * | video_sws = nullptr | 
| Private Member Functions | |
| UsbCam | operator= (const UsbCam &root)=delete | 
| UsbCam () | |
| UsbCam (const UsbCam &root)=delete | |
| virtual | ~UsbCam () | 
| Additional Inherited Members | |
|  Public Member Functions inherited from usb_cam::AbstractV4LUSBCam | |
| virtual | ~AbstractV4LUSBCam () | 
|  Protected Member Functions inherited from usb_cam::AbstractV4LUSBCam | |
| AbstractV4LUSBCam () | |
| AbstractV4LUSBCam (const AbstractV4LUSBCam &root)=delete | |
| 
 | explicitprivate | 
Definition at line 116 of file usb_cam.cpp.
| 
 | privatevirtual | 
Definition at line 312 of file usb_cam.cpp.
| 
 | privatedelete | 
| 
 | staticprotected | 
Definition at line 281 of file usb_cam.cpp.
| 
 | static | 
Definition at line 317 of file usb_cam.cpp.
| 
 | staticprotected | 
Definition at line 68 of file usb_cam.cpp.
| 
 | staticprotected | 
Definition at line 73 of file usb_cam.cpp.
| 
 | staticprotected | 
Definition at line 101 of file usb_cam.cpp.
| 
 | staticprotected | 
Definition at line 78 of file usb_cam.cpp.
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | protected | 
| 
 | staticprotected | 
| 
 | staticprotected | 
| 
 | staticprotected | 
| 
 | staticprotected | 
| 
 | staticprotected | 
| 
 | staticprotected | 
| 
 | staticprotected | 
| 
 | staticprotected | 
| 
 | protected | 
| 
 | staticprotected | 
| 
 | staticprotected | 
| 
 | staticprotected | 
| 
 | staticprotected |