|
From: <jl...@us...> - 2008-11-11 03:59:46
|
Revision: 6509
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=6509&view=rev
Author: jleibs
Date: 2008-11-11 03:59:42 +0000 (Tue, 11 Nov 2008)
Log Message:
-----------
ReFactoring of ImageWrapper to FillImage and reduced CvBridge.
Modified Paths:
--------------
pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp
pkg/trunk/vision/color_calib/libcolorcalib.cpp
pkg/trunk/vision/cv_view/dcam/cv_view.cpp
Added Paths:
-----------
pkg/trunk/image_msgs/include/image_msgs/CvBridge.h
pkg/trunk/image_msgs/include/image_msgs/FillImage.h
Removed Paths:
-------------
pkg/trunk/image_msgs/include/image_msgs/ImageWrapper.h
Modified: pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp
===================================================================
--- pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp 2008-11-11 03:41:56 UTC (rev 6508)
+++ pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp 2008-11-11 03:59:42 UTC (rev 6509)
@@ -35,7 +35,8 @@
#include <cstdio>
#include "ros/node.h"
-#include "image_msgs/ImageWrapper.h"
+#include "image_msgs/Image.h"
+#include "image_msgs/FillImage.h"
#include "image_msgs/CamInfo.h"
#include "image_msgs/StereoInfo.h"
#include "dcam.h"
@@ -51,7 +52,7 @@
bool do_stereo_;
bool do_rectify_;
- image_msgs::ImageWrapper img_wrapper_;
+ image_msgs::Image img_;
image_msgs::CamInfo cam_info_;
image_msgs::StereoInfo stereo_info_;
@@ -234,11 +235,11 @@
if (stcam->stIm->imDisp)
{
- img_wrapper_.fromInterlacedData( "disparity",
- stcam->stIm->imHeight, stcam->stIm->imWidth, 1,
- "mono", "uint16",
- stcam->stIm->imDisp );
- publish("~disparity", img_wrapper_);
+ fillImage(img_, "disparity",
+ stcam->stIm->imHeight, stcam->stIm->imWidth, 1,
+ "mono", "uint16",
+ stcam->stIm->imDisp );
+ publish("~disparity", img_);
stereo_info_.has_disparity = true;
} else {
@@ -276,11 +277,11 @@
if (img->imRawType != COLOR_CODING_NONE)
{
- img_wrapper_.fromInterlacedData( "image_raw",
- img->imHeight, img->imWidth, 1,
- "mono", "byte",
- img->imRaw );
- publish(base_name + std::string("image_raw"), img_wrapper_);
+ fillImage(img_, "image_raw",
+ img->imHeight, img->imWidth, 1,
+ "mono", "byte",
+ img->imRaw );
+ publish(base_name + std::string("image_raw"), img_);
cam_info_.has_image = true;
} else {
cam_info_.has_image = false;
@@ -288,11 +289,11 @@
if (img->imType != COLOR_CODING_NONE)
{
- img_wrapper_.fromInterlacedData( "image",
- img->imHeight, img->imWidth, 1,
- "mono", "byte",
- img->im );
- publish(base_name + std::string("image"), img_wrapper_);
+ fillImage(img_, "image",
+ img->imHeight, img->imWidth, 1,
+ "mono", "byte",
+ img->im );
+ publish(base_name + std::string("image"), img_);
cam_info_.has_image = true;
} else {
cam_info_.has_image = false;
@@ -300,11 +301,11 @@
if (img->imColorType != COLOR_CODING_NONE)
{
- img_wrapper_.fromInterlacedData( "image_color",
- img->imHeight, img->imWidth, 3,
- "rgb", "byte",
- img->imColor );
- publish(base_name + std::string("image_color"), img_wrapper_);
+ fillImage(img_, "image_color",
+ img->imHeight, img->imWidth, 4,
+ "rgba", "byte",
+ img->imColor );
+ publish(base_name + std::string("image_color"), img_);
cam_info_.has_image_color = true;
} else {
cam_info_.has_image_color = false;
@@ -312,11 +313,11 @@
if (img->imRectType != COLOR_CODING_NONE)
{
- img_wrapper_.fromInterlacedData( "image_rect",
- img->imHeight, img->imWidth, 1,
- "mono", "byte",
- img->imRect );
- publish(base_name + std::string("image_rect"), img_wrapper_);
+ fillImage(img_, "image_rect",
+ img->imHeight, img->imWidth, 1,
+ "mono", "byte",
+ img->imRect );
+ publish(base_name + std::string("image_rect"), img_);
cam_info_.has_image_rect = true;
} else {
cam_info_.has_image_rect = false;
@@ -324,11 +325,11 @@
if (img->imRectColorType != COLOR_CODING_NONE)
{
- img_wrapper_.fromInterlacedData( "image_rect_color",
- img->imHeight, img->imWidth, 3,
- "rgb", "byte",
- img->imRectColor );
- publish(base_name + std::string("image_rect_color"), img_wrapper_);
+ fillImage(img_, "image_rect_color",
+ img->imHeight, img->imWidth, 4,
+ "rgba", "byte",
+ img->imRectColor );
+ publish(base_name + std::string("image_rect_color"), img_);
cam_info_.has_image_rect_color = true;
}else {
cam_info_.has_image_rect_color = false;
@@ -352,19 +353,19 @@
advertise<image_msgs::CamInfo>(base_name + std::string("cam_info"), 1);
if (img->imRawType != COLOR_CODING_NONE)
- advertise<image_msgs::ImageWrapper>(base_name + std::string("image_raw"), 1);
+ advertise<image_msgs::Image>(base_name + std::string("image_raw"), 1);
if (img->imType != COLOR_CODING_NONE)
- advertise<image_msgs::ImageWrapper>(base_name + std::string("image"), 1);
+ advertise<image_msgs::Image>(base_name + std::string("image"), 1);
if (img->imColorType != COLOR_CODING_NONE)
- advertise<image_msgs::ImageWrapper>(base_name + std::string("image_color"), 1);
+ advertise<image_msgs::Image>(base_name + std::string("image_color"), 1);
if (img->imRectType != COLOR_CODING_NONE)
- advertise<image_msgs::ImageWrapper>(base_name + std::string("image_rect"), 1);
+ advertise<image_msgs::Image>(base_name + std::string("image_rect"), 1);
if (img->imRectColorType != COLOR_CODING_NONE)
- advertise<image_msgs::ImageWrapper>(base_name + std::string("image_rect_color"), 1);
+ advertise<image_msgs::Image>(base_name + std::string("image_rect_color"), 1);
}
@@ -380,7 +381,7 @@
advertiseImages("~right/", stcam->stIm->imRight);
if (stcam->stIm->imDisp)
- advertise<image_msgs::ImageWrapper>("~disparity", 1);
+ advertise<image_msgs::Image>("~disparity", 1);
}
else
@@ -391,7 +392,7 @@
bool spin()
{
- // Start up the laser
+ // Start up the camera
while (ok())
{
serviceCam();
@@ -406,12 +407,10 @@
{
ros::init(argc, argv);
- //Keep things from dying poorly
DcamNode dc;
dc.spin();
-
ros::fini();
return 0;
}
Added: pkg/trunk/image_msgs/include/image_msgs/CvBridge.h
===================================================================
--- pkg/trunk/image_msgs/include/image_msgs/CvBridge.h (rev 0)
+++ pkg/trunk/image_msgs/include/image_msgs/CvBridge.h 2008-11-11 03:59:42 UTC (rev 6509)
@@ -0,0 +1,91 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* 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 the Willow Garage 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 AND CONTRIBUTORS
+* "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.
+*********************************************************************/
+
+#ifndef CVBRIDGE_HH
+#define CVBRIDGE_HH
+
+#include "image_msgs/Image.h"
+#include "opencv/cxcore.h"
+
+
+namespace image_msgs
+{
+
+ class CvBridge
+ {
+ IplImage* img_;
+ bool owns_data_;
+
+ public:
+
+ CvBridge() : img_(0), owns_data_(false)
+ {
+ img_ = cvCreateImageHeader( cvSize(0,0), IPL_DEPTH_8U, 1 );
+ }
+
+ ~CvBridge()
+ {
+ if (owns_data_)
+ cvReleaseData(&img_);
+
+ cvReleaseImageHeader(&img_);
+ }
+
+
+ inline IplImage* toIpl()
+ {
+ return img_;
+ }
+
+ bool fromImage(Image& rosimg)
+ {
+ if (rosimg.depth == "byte")
+ {
+ cvInitImageHeader(img_, cvSize(rosimg.byte_data.layout.dim[1].size, rosimg.byte_data.layout.dim[0].size), IPL_DEPTH_8U, 1);
+ cvSetData(img_, &(rosimg.byte_data.data[0]), rosimg.byte_data.layout.dim[1].stride);
+ } else if (rosimg.depth == "uint16") {
+ cvInitImageHeader(img_, cvSize(rosimg.uint16_data.layout.dim[1].size, rosimg.uint16_data.layout.dim[0].size), IPL_DEPTH_8U, 1);
+ cvSetData(img_, &(rosimg.uint16_data.data[0]), rosimg.uint16_data.layout.dim[1].stride*sizeof(uint16_t));
+ }
+
+ return true;
+
+ }
+ private:
+
+ };
+}
+
+
+#endif
Added: pkg/trunk/image_msgs/include/image_msgs/FillImage.h
===================================================================
--- pkg/trunk/image_msgs/include/image_msgs/FillImage.h (rev 0)
+++ pkg/trunk/image_msgs/include/image_msgs/FillImage.h 2008-11-11 03:59:42 UTC (rev 6509)
@@ -0,0 +1,103 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* 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 the Willow Garage 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 AND CONTRIBUTORS
+* "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.
+*********************************************************************/
+
+#ifndef FILLIMAGE_HH
+#define FILLIMAGE_HH
+
+#include "image_msgs/Image.h"
+
+namespace image_msgs
+{
+
+ template <class M>
+ void fillImageHelper(M &m,
+ uint32_t sz0, uint32_t st0,
+ uint32_t sz1, uint32_t st1,
+ uint32_t sz2, uint32_t st2,
+ void *d)
+ {
+ m.layout.dim.resize(3);
+ m.layout.dim[0].label = "height";
+ m.layout.dim[0].size = sz0;
+ m.layout.dim[0].stride = st0;
+ m.layout.dim[1].label = "width";
+ m.layout.dim[1].size = sz1;
+ m.layout.dim[1].stride = st1;
+ m.layout.dim[2].label = "channel";
+ m.layout.dim[2].size = sz2;
+ m.layout.dim[2].stride = st2;
+ m.data.resize(st0);
+ memcpy((char*)(&m.data[0]), (char*)(d), st0*sizeof(m.data[0]));
+ }
+
+ bool fillImage(Image& image,
+ std::string label_arg,
+ uint32_t height_arg, uint32_t width_arg, uint32_t channel_arg,
+ std::string encoding_arg, std::string depth_arg,
+ void* data_arg,
+ uint32_t channel_step = 0, uint32_t width_step = 0, uint32_t height_step = 0)
+ {
+ image.label = label_arg;
+ image.encoding = encoding_arg;
+ image.depth = depth_arg;
+
+ if (channel_step == 0)
+ channel_step = channel_arg;
+
+ if (width_step == 0)
+ width_step = width_arg * channel_step;
+
+ if (height_step == 0)
+ height_step = height_arg * width_step;
+
+ if (image.depth == "byte")
+ fillImageHelper(image.byte_data,
+ height_arg, height_step,
+ width_arg, width_step,
+ channel_arg, channel_step,
+ data_arg);
+
+ else if (image.depth == "uint16")
+ fillImageHelper(image.uint16_data,
+ height_arg, height_step,
+ width_arg, width_step,
+ channel_arg, channel_step,
+ data_arg);
+
+ return true;
+ }
+}
+
+
+#endif
Deleted: pkg/trunk/image_msgs/include/image_msgs/ImageWrapper.h
===================================================================
--- pkg/trunk/image_msgs/include/image_msgs/ImageWrapper.h 2008-11-11 03:41:56 UTC (rev 6508)
+++ pkg/trunk/image_msgs/include/image_msgs/ImageWrapper.h 2008-11-11 03:59:42 UTC (rev 6509)
@@ -1,123 +0,0 @@
-/*********************************************************************
-* Software License Agreement (BSD License)
-*
-* Copyright (c) 2008, Willow Garage, Inc.
-* 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 the Willow Garage 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 AND CONTRIBUTORS
-* "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.
-*********************************************************************/
-
-#ifndef IMAGEWRAPPER_HH
-#define IMAGEWRAPPER_HH
-
-#include "image_msgs/Image.h"
-#include "image.h"
-#include "opencv/cxcore.h"
-
-
-namespace image_msgs
-{
-
- class ImageWrapper : public image_msgs::Image
- {
- public:
- bool fromInterlacedData(std::string label_arg,
- uint32_t height_arg, uint32_t width_arg, uint32_t channel_arg,
- std::string encoding_arg, std::string depth_arg,
- void* data_arg,
- uint32_t channel_step = 0, uint32_t width_step = 0, uint32_t height_step = 0)
- {
- label = label_arg;
- encoding = encoding_arg;
- depth = depth_arg;
-
- if (channel_step == 0)
- channel_step = channel_arg;
-
- if (width_step == 0)
- width_step = width_arg * channel_step;
-
- if (height_step == 0)
- height_step = height_arg * width_step;
-
- if (depth == "byte")
- fromDataHelper(byte_data,
- height_arg, height_step,
- width_arg, width_step,
- channel_arg, channel_step,
- data_arg);
-
- else if (depth == "uint16")
- fromDataHelper(uint16_data,
- height_arg, height_step,
- width_arg, width_step,
- channel_arg, channel_step,
- data_arg);
-
- return true;
- }
-
- IplImage* asIplImage()
- {
- IplImage* img;
- if (depth == "byte")
- {
- img = cvCreateImageHeader(cvSize(byte_data.layout.dim[1].size, byte_data.layout.dim[0].size), IPL_DEPTH_8U, 1);
- cvSetData(img, &(byte_data.data[0]), byte_data.layout.dim[1].stride);
- } else if (depth == "uint16") {
- img = cvCreateImageHeader(cvSize(uint16_data.layout.dim[1].size, uint16_data.layout.dim[0].size), IPL_DEPTH_16U, 1);
- cvSetData(img, &(uint16_data.data[0]), uint16_data.layout.dim[1].stride*sizeof(uint16_t));
- }
- return img;
- }
- private:
- template <class M>
- void fromDataHelper(M &m,
- uint32_t sz0, uint32_t st0,
- uint32_t sz1, uint32_t st1,
- uint32_t sz2, uint32_t st2,
- void *d)
- {
- m.layout.dim.resize(3);
- m.layout.dim[0].label = "height";
- m.layout.dim[0].size = sz0;
- m.layout.dim[0].stride = st0;
- m.layout.dim[1].label = "width";
- m.layout.dim[1].size = sz1;
- m.layout.dim[1].stride = st1;
- m.layout.dim[2].label = "channel";
- m.layout.dim[2].size = sz2;
- m.layout.dim[2].stride = st2;
- m.data.resize(st0);
- memcpy((char*)(&m.data[0]), (char*)(d), st0*sizeof(m.data[0]));
- }
- };
-}
-
-
-#endif
Modified: pkg/trunk/vision/color_calib/libcolorcalib.cpp
===================================================================
--- pkg/trunk/vision/color_calib/libcolorcalib.cpp 2008-11-11 03:41:56 UTC (rev 6508)
+++ pkg/trunk/vision/color_calib/libcolorcalib.cpp 2008-11-11 03:59:42 UTC (rev 6509)
@@ -158,7 +158,7 @@
for (int j = 0; j < src->width; j++)
for (int k = 0; k < channels; k++)
((uchar *)(dst->imageData + i*dst->widthStep))[j*dst->nChannels + k] =
- compandmap[((uchar *)(src->imageData + i*src->widthStep))[j*src->nChannels + k] << 4];
+ compandmap[((uchar *)(src->imageData + i*src->widthStep))[j*src->nChannels + k] << 4] >> 2;
}
}
Modified: pkg/trunk/vision/cv_view/dcam/cv_view.cpp
===================================================================
--- pkg/trunk/vision/cv_view/dcam/cv_view.cpp 2008-11-11 03:41:56 UTC (rev 6508)
+++ pkg/trunk/vision/cv_view/dcam/cv_view.cpp 2008-11-11 03:59:42 UTC (rev 6509)
@@ -4,7 +4,8 @@
#include "opencv/cv.h"
#include "opencv/highgui.h"
#include "ros/node.h"
-#include "image_msgs/ImageWrapper.h"
+#include "image_msgs/Image.h"
+#include "image_msgs/CvBridge.h"
using namespace std;
using namespace ros;
@@ -12,7 +13,8 @@
class CvView : public node
{
public:
- image_msgs::ImageWrapper img;
+ image_msgs::Image img;
+ image_msgs::CvBridge bridge;
CvView() : node("cv_view")
{
@@ -21,12 +23,11 @@
}
void image_cb()
{
- IplImage *cv_image = img.asIplImage();
+ bridge.fromImage(img);
- cvShowImage("cv_view", cv_image);
+ cvShowImage("cv_view", bridge.toIpl());
+
cvWaitKey(5);
-
- cvReleaseImageHeader(&cv_image);
}
};
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|