camera.cpp
Go to the documentation of this file.
00001 #include <boost/thread.hpp>
00002 
00003 #include <ros/ros.h>
00004 #include <ros/time.h>
00005 
00006 #include "uvc_cam/uvc_cam.h"
00007 #include "sensor_msgs/Image.h"
00008 #include "sensor_msgs/CompressedImage.h"
00009 #include "sensor_msgs/image_encodings.h"
00010 #include "sensor_msgs/CameraInfo.h"
00011 #include "camera_info_manager/camera_info_manager.h"
00012 #include "image_transport/image_transport.h"
00013 
00014 #include "uvc_camera/camera.h"
00015 
00016 using namespace sensor_msgs;
00017 
00018 namespace uvc_camera {
00019 
00020 Camera::Camera(ros::NodeHandle _comm_nh, ros::NodeHandle _param_nh) :
00021       node(_comm_nh), pnode(_param_nh), it(_comm_nh),
00022       info_mgr(_comm_nh, "camera"), cam(0) {
00023 
00024       /* default config values */
00025       width = 640;
00026       height = 480;
00027       fps = 10;
00028       skip_frames = 0;
00029       frames_to_skip = 0;
00030       device = "/dev/video0";
00031       frame = "camera";
00032       rotate = false;
00033       format = "rgb";
00034 
00035       /* set up information manager */
00036       std::string url, camera_name;
00037       pnode.getParam("camera_info_url", url);
00038       pnode.param<std::string>("camera_name", camera_name, "camera");
00039 
00040       info_mgr.setCameraName(camera_name);
00041       info_mgr.loadCameraInfo(url);
00042 
00043       /* pull other configuration */
00044       pnode.getParam("device", device);
00045 
00046       pnode.getParam("fps", fps);
00047       pnode.getParam("skip_frames", skip_frames);
00048 
00049       pnode.getParam("width", width);
00050       pnode.getParam("height", height);
00051 
00052       pnode.getParam("frame_id", frame);
00053 
00054       pnode.getParam("format", format);
00055 
00056       /* advertise image streams and info streams */
00057       if (format != "jpeg")
00058         pub = it.advertise("image_raw", 1);
00059       else
00060         pubjpeg = node.advertise<CompressedImage>("image_raw/compressed", 1);
00061 
00062       info_pub = node.advertise<CameraInfo>("camera_info", 1);
00063 
00064       /* initialize the cameras */
00065       uvc_cam::Cam::mode_t mode = uvc_cam::Cam::MODE_RGB;
00066       if (format == "jpeg")
00067         mode = uvc_cam::Cam::MODE_MJPG;
00068       cam = new uvc_cam::Cam(device.c_str(), mode, width, height, fps);
00069       cam->set_motion_thresholds(100, -1);
00070 
00071 
00072       bool auto_focus;
00073       if (pnode.getParam("auto_focus", auto_focus)) {
00074         cam->set_v4l2_control(V4L2_CID_FOCUS_AUTO, auto_focus, "auto_focus");
00075       }
00076 
00077       int focus_absolute;
00078       if (pnode.getParam("focus_absolute", focus_absolute)) {
00079         cam->set_v4l2_control(V4L2_CID_FOCUS_ABSOLUTE, focus_absolute, "focus_absolute");
00080       }
00081 
00082       bool auto_exposure;
00083       if (pnode.getParam("auto_exposure", auto_exposure)) {
00084         int val;
00085         if (auto_exposure) {
00086           val = V4L2_EXPOSURE_AUTO;
00087         } else {
00088           val = V4L2_EXPOSURE_MANUAL;
00089         }
00090         cam->set_v4l2_control(V4L2_CID_EXPOSURE_AUTO, val, "auto_exposure");
00091       }
00092 
00093       int exposure_absolute;
00094       if (pnode.getParam("exposure_absolute", exposure_absolute)) {
00095         cam->set_v4l2_control(V4L2_CID_EXPOSURE_ABSOLUTE, exposure_absolute, "exposure_absolute");
00096       }
00097 
00098       int brightness;
00099       if (pnode.getParam("brightness", brightness)) {
00100         cam->set_v4l2_control(V4L2_CID_BRIGHTNESS, brightness, "brightness");
00101       }
00102 
00103       int power_line_frequency;
00104       if (pnode.getParam("power_line_frequency", power_line_frequency)) {
00105         int val;
00106         if (power_line_frequency == 0) {
00107           val = V4L2_CID_POWER_LINE_FREQUENCY_DISABLED;
00108         } else if (power_line_frequency == 50) {
00109           val = V4L2_CID_POWER_LINE_FREQUENCY_50HZ;
00110         } else if (power_line_frequency == 60) {
00111           val = V4L2_CID_POWER_LINE_FREQUENCY_60HZ;
00112         } else {
00113           printf("power_line_frequency=%d not supported. Using auto.\n", power_line_frequency);
00114           val = V4L2_CID_POWER_LINE_FREQUENCY_AUTO;
00115         }
00116         cam->set_v4l2_control(V4L2_CID_POWER_LINE_FREQUENCY, val, "power_line_frequency");
00117       }
00118 
00119       // TODO:
00120       // - add params for
00121       //   contrast
00122       //   saturation
00123       //   hue
00124       //   white balance temperature, auto and manual
00125       //   gamma
00126       //   sharpness
00127       //   backlight compensation
00128       //   exposure auto priority
00129       //   zoom
00130       // - add generic parameter list:
00131       //   [(id0, val0, name0), (id1, val1, name1), ...]
00132 
00133 
00134       /* and turn on the streamer */
00135       ok = true;
00136       image_thread = boost::thread(boost::bind(&Camera::feedImages, this));
00137     }
00138 
00139     void Camera::sendInfo(ImagePtr &image, ros::Time time) {
00140       CameraInfoPtr info(new CameraInfo(info_mgr.getCameraInfo()));
00141 
00142       /* Throw out any CamInfo that's not calibrated to this camera mode */
00143       if (info->K[0] != 0.0 &&
00144            (image->width != info->width
00145               || image->height != info->height)) {
00146         info.reset(new CameraInfo());
00147       }
00148 
00149       /* If we don't have a calibration, set the image dimensions */
00150       if (info->K[0] == 0.0) {
00151         info->width = image->width;
00152         info->height = image->height;
00153       }
00154 
00155       info->header.stamp = time;
00156       info->header.frame_id = frame;
00157 
00158       info_pub.publish(info);
00159     }
00160 
00161     void Camera::sendInfoJpeg(ros::Time time) {
00162       CameraInfoPtr info(new CameraInfo(info_mgr.getCameraInfo()));
00163       info->header.stamp = time;
00164       info->header.frame_id = frame;
00165 
00166       info_pub.publish(info);
00167     }
00168 
00169     void Camera::feedImages() {
00170       unsigned int pair_id = 0;
00171       while (ok) {
00172         unsigned char *img_frame = NULL;
00173         uint32_t bytes_used;
00174 
00175         ros::Time capture_time = ros::Time::now();
00176 
00177         int idx = cam->grab(&img_frame, bytes_used);
00178 
00179         /* Read in every frame the camera generates, but only send each
00180          * (skip_frames + 1)th frame. It's set up this way just because
00181          * this is based on Stereo...
00182          */
00183         if (skip_frames == 0 || frames_to_skip == 0) {
00184           if (img_frame && format != "jpeg") {
00185              ImagePtr image(new Image);
00186 
00187              image->height = height;
00188              image->width = width;
00189              image->step = 3 * width;
00190              image->encoding = image_encodings::RGB8;
00191 
00192              image->header.stamp = capture_time;
00193              image->header.seq = pair_id;
00194 
00195              image->header.frame_id = frame;
00196 
00197              image->data.resize(image->step * image->height);
00198 
00199              memcpy(&image->data[0], img_frame, width*height * 3);
00200 
00201              pub.publish(image);
00202 
00203              sendInfo(image, capture_time);
00204 
00205              ++pair_id;
00206           } else if (img_frame && format == "jpeg") {
00207              CompressedImagePtr image(new CompressedImage);
00208 
00209              image->header.stamp = capture_time;
00210              image->header.seq = pair_id;
00211 
00212              image->header.frame_id = frame;
00213 
00214              image->data.resize(bytes_used);
00215 
00216              memcpy(&image->data[0], img_frame, bytes_used);
00217 
00218              pubjpeg.publish(image);
00219 
00220              sendInfoJpeg(capture_time);
00221 
00222              ++pair_id;
00223           }
00224 
00225           frames_to_skip = skip_frames;
00226         } else {
00227           frames_to_skip--;
00228         }
00229 
00230         if (img_frame) cam->release(idx);
00231       }
00232     }
00233 
00234     Camera::~Camera() {
00235       ok = false;
00236       image_thread.join();
00237       if (cam) delete cam;
00238     }
00239 
00240 
00241 };
00242 


uvc_camera
Author(s): Ken Tossell
autogenerated on Sun Oct 5 2014 22:47:18