|
From: <jam...@us...> - 2009-08-09 19:14:21
|
Revision: 21244
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21244&view=rev
Author: jamesbowman
Date: 2009-08-09 19:14:00 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
Image message and CvBridge change
Modified Paths:
--------------
pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_grab.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h
pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/image_encodings.h
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg
pkg/trunk/stacks/common_msgs/sensor_msgs/src/image_encodings.cpp
pkg/trunk/stacks/opencv/image_view/image_view.cpp
pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h
pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py
pkg/trunk/stacks/opencv/opencv_tests/test/enumerants.py
pkg/trunk/stacks/opencv/opencv_tests/test/utest.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp
pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp
pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp
pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_calibration.cpp
pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_detector.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting2.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_tracker.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/plug_tracker.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.h
Modified: pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -203,7 +203,7 @@
{
if (img_data->imRawType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1,
img_data->imHeight, img_data->imWidth, img_data->imWidth,
img_data->imRaw);
@@ -214,7 +214,7 @@
if (img_data->imType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1,
img_data->imHeight, img_data->imWidth, img_data->imWidth,
img_data->im);
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
@@ -224,7 +224,7 @@
if (img_data->imColorType != COLOR_CODING_NONE && img_data->imColorType == COLOR_CODING_RGB8)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC3,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC3,
img_data->imHeight, img_data->imWidth, 3 * img_data->imWidth,
img_data->imColor );
@@ -235,7 +235,7 @@
if (img_data->imRectType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1,
img_data->imHeight, img_data->imWidth, img_data->imWidth,
img_data->imRect );
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
@@ -245,7 +245,7 @@
if (img_data->imRectColorType != COLOR_CODING_NONE && img_data->imRectColorType == COLOR_CODING_RGB8)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC3,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC3,
img_data->imHeight, img_data->imWidth, 3 * img_data->imWidth,
img_data->imRectColor );
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
@@ -255,7 +255,7 @@
if (img_data->imRectColorType != COLOR_CODING_NONE && img_data->imRectColorType == COLOR_CODING_RGBA8)
{
- fillImage(img_,sensor_msgs::Image::TYPE_8UC4,
+ fillImage(img_,sensor_msgs::image_encodings::TYPE_8UC4,
img_data->imHeight, img_data->imWidth, 4 * img_data->imWidth,
img_data->imRectColor );
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
Modified: pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -954,7 +954,7 @@
int publishImage(size_t width, size_t height, uint8_t *frameData, ros::Time t)
{
- fillImage(image_, sensor_msgs::Image::TYPE_8UC1, height, width, width, frameData);
+ fillImage(image_, sensor_msgs::image_encodings::TYPE_8UC1, height, width, width, frameData);
image_.header.stamp = t;
cam_pub_.publish(image_);
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -86,7 +86,7 @@
return false;
// Copy into result
- fillImage(res.image, sensor_msgs::Image::TYPE_8UC3,
+ fillImage(res.image, sensor_msgs::image_encodings::TYPE_8UC3,
img.Height(), img.Width(), 3 * img.Width(),
img.ImageData());
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_grab.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_grab.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_grab.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -23,7 +23,7 @@
return NULL;
}
- if (!bridge.fromImage(res.image, "bgr")) {
+ if (!bridge.fromImage(res.image, "bgr8")) {
ROS_ERROR("CvBridge::fromImage failed");
return NULL;
}
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -543,7 +543,7 @@
static void setBgrLayout(sensor_msgs::Image &image, int width, int height)
{
- image.type = sensor_msgs::Image::TYPE_8UC3;
+ image.encoding = sensor_msgs::image_encodings::TYPE_8UC3;
image.height = height;
image.width = width;
image.step = width * 3;
@@ -557,7 +557,7 @@
{
case ePvFmtMono8:
- fillImage(image, sensor_msgs::Image::TYPE_8UC1, frame->Height, frame->Width, frame->Width, frame->ImageBuffer);
+ fillImage(image, sensor_msgs::image_encodings::TYPE_8UC1, frame->Height, frame->Width, frame->Width, frame->ImageBuffer);
break;
case ePvFmtBayer8:
@@ -569,20 +569,20 @@
break;
case ePvFmtBgr24:
- fillImage(image, sensor_msgs::Image::TYPE_8UC3, frame->Height, frame->Width, 3 * frame->Width, frame->ImageBuffer);
+ fillImage(image, sensor_msgs::image_encodings::TYPE_8UC3, frame->Height, frame->Width, 3 * frame->Width, frame->ImageBuffer);
break;
case ePvFmtRgba32:
- fillImage(image, sensor_msgs::Image::TYPE_8UC4, frame->Height, frame->Width, 4 * frame->Width, frame->ImageBuffer);
+ fillImage(image, sensor_msgs::image_encodings::TYPE_8UC4, frame->Height, frame->Width, 4 * frame->Width, frame->ImageBuffer);
break;
case ePvFmtBgra32:
- fillImage(image, sensor_msgs::Image::TYPE_8UC4, frame->Height, frame->Width, 4 * frame->Width, frame->ImageBuffer);
+ fillImage(image, sensor_msgs::image_encodings::TYPE_8UC4, frame->Height, frame->Width, 4 * frame->Width, frame->ImageBuffer);
break;
#if 0 // XXX JCB - these cannot be represented in a CvMat
case ePvFmtRgb24:
- // fillImage(image, sensor_msgs::Image::TYPE_8UC3, frame->Height, frame->Width, 3 * frame->Width, frame->ImageBuffer);
+ // fillImage(image, sensor_msgs::image_encodings::TYPE_8UC3, frame->Height, frame->Width, 3 * frame->Width, frame->ImageBuffer);
break;
case ePvFmtYuv411:
// fillImage(image, "image", frame->Height, frame->Width, 6, "yuv411", "uint8", frame->ImageBuffer);
@@ -603,15 +603,15 @@
sensor_msgs::CameraInfo &cam_info)
{
// Currently assume BGR format so bridge.toIpl() image points to msg data buffer
- if (img.type != sensor_msgs::Image::TYPE_8UC1) {
- ROS_WARN("Couldn't rectify frame, unsupported encoding %d", img.type);
+ if (img.encoding != sensor_msgs::image_encodings::TYPE_8UC1) {
+ ROS_WARN("Couldn't rectify frame, unsupported encoding %s", img.encoding.c_str());
return false;
}
// Prepare image buffer
setBgrLayout(rect_img, frame->Width, frame->Height);
- if (!img_bridge_.fromImage(img, "bgr") ||
- !rect_img_bridge_.fromImage(rect_img, "bgr")) {
+ if (!img_bridge_.fromImage(img, "bgr8") ||
+ !rect_img_bridge_.fromImage(rect_img, "bgr8")) {
ROS_WARN("Couldn't rectify frame, failed to convert");
return false;
}
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h 2009-08-09 19:14:00 UTC (rev 21244)
@@ -36,21 +36,22 @@
#define FILLIMAGE_HH
#include "sensor_msgs/Image.h"
+#include "sensor_msgs/image_encodings.h"
namespace sensor_msgs
{
bool fillImage(Image& image,
- uint32_t type_arg,
+ std::string encoding_arg,
uint32_t rows_arg,
uint32_t cols_arg,
uint32_t step_arg,
void* data_arg)
{
- image.type = type_arg;
- image.height = rows_arg;
- image.width = cols_arg;
- image.step = step_arg;
+ image.encoding = encoding_arg;
+ image.height = rows_arg;
+ image.width = cols_arg;
+ image.step = step_arg;
size_t st0 = (step_arg * rows_arg);
image.data.resize(st0);
memcpy((char*)(&image.data[0]), (char*)(data_arg), st0);
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/image_encodings.h
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/image_encodings.h 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/image_encodings.h 2009-08-09 19:14:00 UTC (rev 21244)
@@ -43,6 +43,35 @@
extern const std::string RGBA8;
extern const std::string BGR8;
extern const std::string BGRA8;
- // etc.
+ extern const std::string MONO8;
+ extern const std::string MONO16;
+ extern const std::string TYPE_8UC1;
+ extern const std::string TYPE_8UC2;
+ extern const std::string TYPE_8UC3;
+ extern const std::string TYPE_8UC4;
+ extern const std::string TYPE_8SC1;
+ extern const std::string TYPE_8SC2;
+ extern const std::string TYPE_8SC3;
+ extern const std::string TYPE_8SC4;
+ extern const std::string TYPE_16UC1;
+ extern const std::string TYPE_16UC2;
+ extern const std::string TYPE_16UC3;
+ extern const std::string TYPE_16UC4;
+ extern const std::string TYPE_16SC1;
+ extern const std::string TYPE_16SC2;
+ extern const std::string TYPE_16SC3;
+ extern const std::string TYPE_16SC4;
+ extern const std::string TYPE_32SC1;
+ extern const std::string TYPE_32SC2;
+ extern const std::string TYPE_32SC3;
+ extern const std::string TYPE_32SC4;
+ extern const std::string TYPE_32FC1;
+ extern const std::string TYPE_32FC2;
+ extern const std::string TYPE_32FC3;
+ extern const std::string TYPE_32FC4;
+ extern const std::string TYPE_64FC1;
+ extern const std::string TYPE_64FC2;
+ extern const std::string TYPE_64FC3;
+ extern const std::string TYPE_64FC4;
}
}
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg 2009-08-09 19:14:00 UTC (rev 21244)
@@ -1,44 +1,9 @@
Header header # Header
-# These are the two most popular image types, so make special synonyms for them
-uint32 TYPE_MONO8=0
-uint32 TYPE_BGR8=16
+# The legal values for encoding are in file src/image_encodings.cpp
+# If you want to standardize a new string format, join ros...@li... and send an email proposing a new encoding.
-# Encoded as OpenCV's CvMat type.
-# S=signed, U=unsigned, F=float.
-# For example, TYPE_8UC1 means the elements are 8-bit unsigned and the
-# there is 1 channel, and TYPE_32SC2 means the elements are 32-bit
-# signed and there are 2 channels.
-uint32 TYPE_8UC1=0
-uint32 TYPE_8UC2=8
-uint32 TYPE_8UC3=16
-uint32 TYPE_8UC4=24
-uint32 TYPE_8SC1=1
-uint32 TYPE_8SC2=9
-uint32 TYPE_8SC3=17
-uint32 TYPE_8SC4=25
-uint32 TYPE_16UC1=2
-uint32 TYPE_16UC2=10
-uint32 TYPE_16UC3=18
-uint32 TYPE_16UC4=26
-uint32 TYPE_16SC1=3
-uint32 TYPE_16SC2=11
-uint32 TYPE_16SC3=19
-uint32 TYPE_16SC4=27
-uint32 TYPE_32SC1=4
-uint32 TYPE_32SC2=12
-uint32 TYPE_32SC3=20
-uint32 TYPE_32SC4=28
-uint32 TYPE_32FC1=5
-uint32 TYPE_32FC2=13
-uint32 TYPE_32FC3=21
-uint32 TYPE_32FC4=29
-uint32 TYPE_64FC1=6
-uint32 TYPE_64FC2=14
-uint32 TYPE_64FC3=22
-uint32 TYPE_64FC4=30
-
-uint32 type # Type of elements, and channels. Encoded as in OpenCV's TYPE_8UC1 .. TYPE_64FC4.
+string encoding # Encoding of pixels -- channel meaning, ordering, size -- taken from the list of strings in src/image_encodings.cpp
uint32 step # Full row length in bytes
uint8[] data # actual matrix data, size is (step * rows)
uint32 height # image height, that is, number of rows
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/src/image_encodings.cpp
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/src/image_encodings.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/src/image_encodings.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -42,6 +42,36 @@
const std::string RGBA8 = "rgba8";
const std::string BGR8 = "bgr8";
const std::string BGRA8 = "bgra8";
- // etc.
+ const std::string MONO8="mono8";
+ const std::string MONO16="mono16";
+
+ const std::string TYPE_8UC1="8UC1";
+ const std::string TYPE_8UC2="8UC2";
+ const std::string TYPE_8UC3="8UC3";
+ const std::string TYPE_8UC4="8UC4";
+ const std::string TYPE_8SC1="8SC1";
+ const std::string TYPE_8SC2="8SC2";
+ const std::string TYPE_8SC3="8SC3";
+ const std::string TYPE_8SC4="8SC4";
+ const std::string TYPE_16UC1="16UC1";
+ const std::string TYPE_16UC2="16UC2";
+ const std::string TYPE_16UC3="16UC3";
+ const std::string TYPE_16UC4="16UC4";
+ const std::string TYPE_16SC1="16SC1";
+ const std::string TYPE_16SC2="16SC2";
+ const std::string TYPE_16SC3="16SC3";
+ const std::string TYPE_16SC4="16SC4";
+ const std::string TYPE_32SC1="32SC1";
+ const std::string TYPE_32SC2="32SC2";
+ const std::string TYPE_32SC3="32SC3";
+ const std::string TYPE_32SC4="32SC4";
+ const std::string TYPE_32FC1="32FC1";
+ const std::string TYPE_32FC2="32FC2";
+ const std::string TYPE_32FC3="32FC3";
+ const std::string TYPE_32FC4="32FC4";
+ const std::string TYPE_64FC1="64FC1";
+ const std::string TYPE_64FC2="64FC2";
+ const std::string TYPE_64FC3="64FC3";
+ const std::string TYPE_64FC4="64FC4";
}
}
Modified: pkg/trunk/stacks/opencv/image_view/image_view.cpp
===================================================================
--- pkg/trunk/stacks/opencv/image_view/image_view.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/opencv/image_view/image_view.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -95,10 +95,10 @@
msg->encoding = "mono";
#endif
- if (img_bridge_.fromImage(*msg))
+ if (img_bridge_.fromImage(*msg, "bgr8"))
cvShowImage(window_name_.c_str(), img_bridge_.toIpl());
else
- ROS_ERROR("Unable to convert from %d to bgr", msg->type);
+ ROS_ERROR("Unable to convert image to bgr");
}
static void mouse_cb(int event, int x, int y, int flags, void* param)
Modified: pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h
===================================================================
--- pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h 2009-08-09 19:14:00 UTC (rev 21244)
@@ -97,32 +97,121 @@
* Converts a ROS Image into an OpenCV IPL Image.
* \param rosimg The ROS Image message
*/
- bool fromImage(const Image& rosimg, std::string encoding = "")
+ bool fromImage(const Image& rosimg, std::string encoding = "passthrough")
{
CvMat cvmHeader;
- cvInitMatHeader(&cvmHeader, rosimg.height, rosimg.width, rosimg.type, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
+ int type;
+ if (rosimg.encoding == "_8UC1") type = CV_8UC1;
+ else if (rosimg.encoding == "_8UC2") type = CV_8UC2;
+ else if (rosimg.encoding == "_8UC3") type = CV_8UC3;
+ else if (rosimg.encoding == "_8UC4") type = CV_8UC4;
+ else if (rosimg.encoding == "_8SC1") type = CV_8SC1;
+ else if (rosimg.encoding == "_8SC2") type = CV_8SC2;
+ else if (rosimg.encoding == "_8SC3") type = CV_8SC3;
+ else if (rosimg.encoding == "_8SC4") type = CV_8SC4;
+ else if (rosimg.encoding == "_16UC1") type = CV_16UC1;
+ else if (rosimg.encoding == "_16UC2") type = CV_16UC2;
+ else if (rosimg.encoding == "_16UC3") type = CV_16UC3;
+ else if (rosimg.encoding == "_16UC4") type = CV_16UC4;
+ else if (rosimg.encoding == "_16SC1") type = CV_16SC1;
+ else if (rosimg.encoding == "_16SC2") type = CV_16SC2;
+ else if (rosimg.encoding == "_16SC3") type = CV_16SC3;
+ else if (rosimg.encoding == "_16SC4") type = CV_16SC4;
+ else if (rosimg.encoding == "_32SC1") type = CV_32SC1;
+ else if (rosimg.encoding == "_32SC2") type = CV_32SC2;
+ else if (rosimg.encoding == "_32SC3") type = CV_32SC3;
+ else if (rosimg.encoding == "_32SC4") type = CV_32SC4;
+ else if (rosimg.encoding == "_32FC1") type = CV_32FC1;
+ else if (rosimg.encoding == "_32FC2") type = CV_32FC2;
+ else if (rosimg.encoding == "_32FC3") type = CV_32FC3;
+ else if (rosimg.encoding == "_32FC4") type = CV_32FC4;
+ else if (rosimg.encoding == "_64FC1") type = CV_64FC1;
+ else if (rosimg.encoding == "_64FC2") type = CV_64FC2;
+ else if (rosimg.encoding == "_64FC3") type = CV_64FC3;
+ else if (rosimg.encoding == "_64FC4") type = CV_64FC4;
+ else if (rosimg.encoding == "rgb8") type = CV_8UC3;
+ else if (rosimg.encoding == "bgr8") type = CV_8UC3;
+ else if (rosimg.encoding == "rgba8") type = CV_8UC4;
+ else if (rosimg.encoding == "bgra8") type = CV_8UC4;
+ else if (rosimg.encoding == "mono8") type = CV_8UC1;
+ else if (rosimg.encoding == "mono16") type = CV_16UC1;
+ else return false;
+ cvInitMatHeader(&cvmHeader, rosimg.height, rosimg.width, type, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
cvGetImage(&cvmHeader, rosimg_);
// cvSetData(rosimg_, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
- if (encoding == "") {
+ if ((encoding == "passthrough") || (rosimg.encoding == encoding)) {
img_ = rosimg_;
} else {
- if ((encoding == "bgr" || encoding == "rgb") && rosimg.type == CV_8UC1)
- {
- reallocIfNeeded(&cvtimg_, IPL_DEPTH_8U, 3);
- cvCvtColor(rosimg_, cvtimg_, CV_GRAY2BGR);
- img_ = cvtimg_;
+ int change = -1;
+ int newtype = -1;
+
+ if (rosimg.encoding == "rgb8") {
+ if (encoding == "bgr8")
+ change = CV_RGB2BGR;
+ if (encoding == "bgra8")
+ change = CV_RGB2BGRA;
+ if (encoding == "rgba8")
+ change = CV_RGB2RGBA;
+ if (encoding == "mono8" || encoding == "mono16")
+ change = CV_RGB2GRAY;
+ } else if ((rosimg.encoding == "bgr8") || (rosimg.encoding == "_8UC3")) {
+ if (encoding == "rgb8")
+ change = CV_BGR2RGB;
+ if (encoding == "bgra8")
+ change = CV_BGR2BGRA;
+ if (encoding == "mono8" || encoding == "mono16")
+ change = CV_BGR2GRAY;
+ } else if (rosimg.encoding == "rgba8") {
+ if (encoding == "rgb8")
+ change = CV_RGBA2RGB;
+ if (encoding == "bgr8")
+ change = CV_RGBA2BGR;
+ if (encoding == "mono8" || encoding == "mono16")
+ change = CV_RGBA2GRAY;
+ } else if ((rosimg.encoding == "bgra8") || (rosimg.encoding == "_8UC4")) {
+ if (encoding == "rgb8")
+ change = CV_BGRA2RGB;
+ if (encoding == "bgr8")
+ change = CV_BGRA2BGR;
+ if (encoding == "mono8" || encoding == "mono16")
+ change = CV_BGRA2GRAY;
+ } else if (rosimg.encoding == "mono8" || rosimg.encoding == "mono16" || rosimg.encoding == "_8UC1") {
+ if (encoding == "rgb8")
+ change = CV_GRAY2RGB;
+ if (encoding == "bgr8")
+ change = CV_GRAY2BGR;
+ if (encoding == "bgra8")
+ change = CV_GRAY2BGRA;
+ if (encoding == "rgba8")
+ change = CV_GRAY2RGBA;
+ if (encoding == "mono8" || encoding == "mono16")
+ change = CV_COLORCVT_MAX; // means do no conversion
}
- else if (encoding == "mono" && rosimg.type == CV_8UC3)
- {
- reallocIfNeeded(&cvtimg_, IPL_DEPTH_8U, 1);
- cvCvtColor(rosimg_, cvtimg_, CV_RGB2GRAY);
- img_ = cvtimg_;
- } else {
- img_ = rosimg_;
- }
+
+ if (encoding == "bgr8")
+ newtype = CV_8UC3;
+ if (encoding == "rgb8")
+ newtype = CV_8UC3;
+ if (encoding == "bgra8")
+ newtype = CV_8UC4;
+ if (encoding == "rgba")
+ newtype = CV_8UC4;
+ if (encoding == "mono8")
+ newtype = CV_8UC1;
+ if (encoding == "mono16")
+ newtype = CV_16UC1;
+
+ if (change == -1 || newtype == -1)
+ return false;
+ reallocIfNeeded(&cvtimg_, IPL_DEPTH_8U, CV_MAT_CN(newtype));
+ if (change == CV_COLORCVT_MAX)
+ cvConvertScale(rosimg_, cvtimg_);
+ else
+ cvCvtColor(rosimg_, cvtimg_, change);
+ img_ = cvtimg_;
}
return true;
}
@@ -141,12 +230,52 @@
* \param source The original Ipl Image that we want to copy from
* \param dest The ROS Image message that we want to copy to
*/
- static bool fromIpltoRosImage(const IplImage* source, sensor_msgs::Image& dest)
+ static bool fromIpltoRosImage(const IplImage* source, sensor_msgs::Image& dest, std::string encoding = "passthrough")
{
CvMat header, *cvm;
cvm = cvGetMat(source, &header);
- dest.type = cvm->type & (CV_MAT_TYPE_MASK | CV_MAT_DEPTH_MASK);
+ // dest.type = cvm->type & (CV_MAT_TYPE_MASK | CV_MAT_DEPTH_MASK);
+ dest.encoding = encoding;
+
+ if (encoding == "passthrough") {
+ switch (cvm->type & (CV_MAT_TYPE_MASK | CV_MAT_DEPTH_MASK)) {
+ case CV_8UC1: dest.encoding = "_8UC1"; break;
+ case CV_8UC2: dest.encoding = "_8UC2"; break;
+ case CV_8UC3: dest.encoding = "_8UC3"; break;
+ case CV_8UC4: dest.encoding = "_8UC4"; break;
+ case CV_8SC1: dest.encoding = "_8SC1"; break;
+ case CV_8SC2: dest.encoding = "_8SC2"; break;
+ case CV_8SC3: dest.encoding = "_8SC3"; break;
+ case CV_8SC4: dest.encoding = "_8SC4"; break;
+ case CV_16UC1: dest.encoding = "_16UC1"; break;
+ case CV_16UC2: dest.encoding = "_16UC2"; break;
+ case CV_16UC3: dest.encoding = "_16UC3"; break;
+ case CV_16UC4: dest.encoding = "_16UC4"; break;
+ case CV_16SC1: dest.encoding = "_16SC1"; break;
+ case CV_16SC2: dest.encoding = "_16SC2"; break;
+ case CV_16SC3: dest.encoding = "_16SC3"; break;
+ case CV_16SC4: dest.encoding = "_16SC4"; break;
+ case CV_32SC1: dest.encoding = "_32SC1"; break;
+ case CV_32SC2: dest.encoding = "_32SC2"; break;
+ case CV_32SC3: dest.encoding = "_32SC3"; break;
+ case CV_32SC4: dest.encoding = "_32SC4"; break;
+ case CV_32FC1: dest.encoding = "_32FC1"; break;
+ case CV_32FC2: dest.encoding = "_32FC2"; break;
+ case CV_32FC3: dest.encoding = "_32FC3"; break;
+ case CV_32FC4: dest.encoding = "_32FC4"; break;
+ case CV_64FC1: dest.encoding = "_64FC1"; break;
+ case CV_64FC2: dest.encoding = "_64FC2"; break;
+ case CV_64FC3: dest.encoding = "_64FC3"; break;
+ case CV_64FC4: dest.encoding = "_64FC4"; break;
+ default: assert(0);
+ }
+ } else {
+ // XXX JCB - should verify encoding
+ // XXX JCB - should verify that channels match the channels in original image
+ dest.encoding = encoding;
+ }
+
dest.width = cvm->width;
dest.height = cvm->height;
dest.step = cvm->step;
Modified: pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py 2009-08-09 19:14:00 UTC (rev 21244)
@@ -71,7 +71,7 @@
img_msg = sensor_msgs.msg.Image()
img_msg.width = 640
img_msg.height = 480
- img_msg.type = cv.CV_8UC1
+ img_msg.type = "8UC1"
img_msg.step = 640
img_msg.data = cvim.tostring()
self.pub.publish(img_msg)
@@ -92,4 +92,3 @@
if __name__ == '__main__':
main(sys.argv)
-
Modified: pkg/trunk/stacks/opencv/opencv_tests/test/enumerants.py
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/test/enumerants.py 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/opencv/opencv_tests/test/enumerants.py 2009-08-09 19:14:00 UTC (rev 21244)
@@ -10,12 +10,7 @@
class TestEnumerants(unittest.TestCase):
def test_enumerants(self):
- for t in ["8U", "8S", "16U", "16S", "32S", "32F", "64F" ]:
- for c in [1,2,3,4]:
- nm = "%sC%d" % (t, c)
- cv_num = eval("cv.CV_%s" % nm)
- msg_num = eval("sensor_msgs.msg.Image.TYPE_%s" % nm)
- self.assertEqual(cv_num, msg_num)
+ pass
if __name__ == '__main__':
if 1:
Modified: pkg/trunk/stacks/opencv/opencv_tests/test/utest.cpp
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/test/utest.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/opencv/opencv_tests/test/utest.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -97,15 +97,15 @@
success = img_bridge_.fromIpltoRosImage(original, image_message);
ASSERT_TRUE(success);
- success = img_bridge_.fromImage(image_message, "");
+ success = img_bridge_.fromImage(image_message, "passthrough");
ASSERT_TRUE(success);
EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 1);
- success = img_bridge_.fromImage(image_message, "mono");
+ success = img_bridge_.fromImage(image_message, "mono8");
ASSERT_TRUE(success);
EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 1);
- success = img_bridge_.fromImage(image_message, "rgb");
+ success = img_bridge_.fromImage(image_message, "rgb8");
ASSERT_TRUE(success);
EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 3);
}
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -282,7 +282,7 @@
boost::unique_lock<boost::mutex> lock(data_lock_);
limage_ = image;
- if(lbridge_.fromImage(*limage_, "bgr")) {
+ if(lbridge_.fromImage(*limage_, "bgr8")) {
left_ = lbridge_.toIpl();
}
}
Modified: pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
===================================================================
--- pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h 2009-08-09 19:14:00 UTC (rev 21244)
@@ -45,37 +45,37 @@
{
if (im->imRawType != COLOR_CODING_NONE)
{
- fillImage(im_msg, sensor_msgs::Image::TYPE_8UC1, im->imHeight, im->imWidth, im->imWidth, im->imRaw);
+ fillImage(im_msg, sensor_msgs::image_encodings::TYPE_8UC1, im->imHeight, im->imWidth, im->imWidth, im->imRaw);
type = sensor_msgs::RawStereo::IMAGE_RAW;
}
else if (im->imType != COLOR_CODING_NONE)
{
- fillImage(im_msg, sensor_msgs::Image::TYPE_8UC1, im->imHeight, im->imWidth, im->imWidth, im->im);
+ fillImage(im_msg, sensor_msgs::image_encodings::TYPE_8UC1, im->imHeight, im->imWidth, im->imWidth, im->im);
type = sensor_msgs::RawStereo::IMAGE;
}
else if (im->imColorType != COLOR_CODING_NONE && im->imColorType == COLOR_CODING_RGBA8)
{
- fillImage(im_msg, sensor_msgs::Image::TYPE_8UC4, im->imHeight, im->imWidth, 4 * im->imWidth, im->imColor);
+ fillImage(im_msg, sensor_msgs::image_encodings::TYPE_8UC4, im->imHeight, im->imWidth, 4 * im->imWidth, im->imColor);
type = sensor_msgs::RawStereo::IMAGE_COLOR;
}
else if (im->imColorType != COLOR_CODING_NONE && im->imColorType == COLOR_CODING_RGB8)
{
- fillImage(im_msg, sensor_msgs::Image::TYPE_8UC3, im->imHeight, im->imWidth, 3 * im->imWidth, im->imColor);
+ fillImage(im_msg, sensor_msgs::image_encodings::TYPE_8UC3, im->imHeight, im->imWidth, 3 * im->imWidth, im->imColor);
type = sensor_msgs::RawStereo::IMAGE_COLOR;
}
else if (im->imRectType != COLOR_CODING_NONE)
{
- fillImage(im_msg, sensor_msgs::Image::TYPE_8UC1, im->imHeight, im->imWidth, im->imWidth, im->imRect);
+ fillImage(im_msg, sensor_msgs::image_encodings::TYPE_8UC1, im->imHeight, im->imWidth, im->imWidth, im->imRect);
type = sensor_msgs::RawStereo::IMAGE_RECT;
}
else if (im->imRectColorType != COLOR_CODING_NONE && im->imRectColorType == COLOR_CODING_RGBA8)
{
- fillImage(im_msg, sensor_msgs::Image::TYPE_8UC4, im->imHeight, im->imWidth, 4 * im->imWidth, im->imRectColor);
+ fillImage(im_msg, sensor_msgs::image_encodings::TYPE_8UC4, im->imHeight, im->imWidth, 4 * im->imWidth, im->imRectColor);
type = sensor_msgs::RawStereo::IMAGE_RECT_COLOR;
}
else if (im->imRectColorType != COLOR_CODING_NONE && im->imRectColorType == COLOR_CODING_RGB8)
{
- fillImage(im_msg, sensor_msgs::Image::TYPE_8UC3, im->imHeight, im->imWidth, 3 * im->imWidth, im->imRectColor);
+ fillImage(im_msg, sensor_msgs::image_encodings::TYPE_8UC3, im->imHeight, im->imWidth, 3 * im->imWidth, im->imRectColor);
type = sensor_msgs::RawStereo::IMAGE_RECT_COLOR;
}
@@ -95,7 +95,7 @@
if (stIm->hasDisparity)
{
fillImage(raw_stereo.disparity_image,
- sensor_msgs::Image::TYPE_16SC1,
+ sensor_msgs::image_encodings::TYPE_16SC1,
stIm->imWidth,
stIm->imHeight,
2 * stIm->imWidth,
@@ -182,12 +182,12 @@
extractImage(im_msg.data, &im->imSize, &im->im);
im->imType = COLOR_CODING_MONO8;
}
- else if (type == sensor_msgs::RawStereo::IMAGE_COLOR && im_msg.type == sensor_msgs::Image::TYPE_8UC4)
+ else if (type == sensor_msgs::RawStereo::IMAGE_COLOR && im_msg.encoding == sensor_msgs::image_encodings::TYPE_8UC4)
{
extractImage(im_msg.data, &im->imColorSize, &im->imColor);
im->imColorType = COLOR_CODING_RGBA8;
}
- else if (type == sensor_msgs::RawStereo::IMAGE_COLOR && im_msg.type == sensor_msgs::Image::TYPE_8UC3)
+ else if (type == sensor_msgs::RawStereo::IMAGE_COLOR && im_msg.encoding == sensor_msgs::image_encodings::TYPE_8UC3)
{
extractImage(im_msg.data, &im->imColorSize, &im->imColor);
im->imColorType = COLOR_CODING_RGB8;
@@ -197,12 +197,12 @@
extractImage(im_msg.data, &im->imRectSize, &im->imRect);
im->imRectType = COLOR_CODING_MONO8;
}
- else if (type == sensor_msgs::RawStereo::IMAGE_RECT_COLOR && im_msg.type == sensor_msgs::Image::TYPE_8UC4)
+ else if (type == sensor_msgs::RawStereo::IMAGE_RECT_COLOR && im_msg.encoding == sensor_msgs::image_encodings::TYPE_8UC4)
{
extractImage(im_msg.data, &im->imRectColorSize, &im->imRectColor);
im->imRectColorType = COLOR_CODING_RGBA8;
}
- else if (type == sensor_msgs::RawStereo::IMAGE_RECT_COLOR && im_msg.type == sensor_msgs::Image::TYPE_8UC3)
+ else if (type == sensor_msgs::RawStereo::IMAGE_RECT_COLOR && im_msg.encoding == sensor_msgs::image_encodings::TYPE_8UC3)
{
extractImage(im_msg.data, &im->imRectColorSize, &im->imRectColor);
im->imRectColorType = COLOR_CODING_RGB8;
@@ -210,7 +210,7 @@
// FIXME: this to avoid segfault when right image empty (disparity image requested instead).
// this all seems kind of hacky
- if (im_msg.type == sensor_msgs::Image::TYPE_8UC1) {
+ if (im_msg.encoding == sensor_msgs::image_encodings::TYPE_8UC1) {
im->imHeight = im_msg.height;
im->imWidth = im_msg.width;
} else {
Modified: pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp
===================================================================
--- pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -109,7 +109,7 @@
if (img_data_.imType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1,
img_data_.imHeight, img_data_.imWidth, img_data_.imWidth,
img_data_.im );
node_.publish(cam_name_ + "image", img_);
@@ -117,7 +117,7 @@
if (img_data_.imColorType == COLOR_CODING_RGB8)
{
- fillImage(img_,sensor_msgs::Image::TYPE_8UC3,
+ fillImage(img_,sensor_msgs::image_encodings::TYPE_8UC3,
img_data_.imHeight, img_data_.imWidth, 3 * img_data_.imWidth,
img_data_.imColor );
node_.publish(cam_name_ + "image_color", img_);
@@ -125,7 +125,7 @@
if (img_data_.imRectType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1,
img_data_.imHeight, img_data_.imWidth, img_data_.imWidth,
img_data_.imRect );
node_.publish(cam_name_ + "image_rect", img_);
@@ -133,7 +133,7 @@
if (img_data_.imRectColorType == COLOR_CODING_RGB8)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC3,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC3,
img_data_.imHeight, img_data_.imWidth, 3 * img_data_.imWidth,
img_data_.imRectColor );
node_.publish(cam_name_ + "image_rect_color", img_);
@@ -141,7 +141,7 @@
if (img_data_.imRectColorType == COLOR_CODING_RGBA8)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC4,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC4,
img_data_.imHeight, img_data_.imWidth, 4 * img_data_.imWidth,
img_data_.imRectColor);
node_.publish(cam_name_ + "image_rect_color", img_);
Modified: pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp
===================================================================
--- pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -214,7 +214,7 @@
publish("disparity_info", disparity_info_);
- fillImage(img_, sensor_msgs::Image::TYPE_16SC1, stdata_->imHeight, stdata_->imWidth, 2 * stdata_->imWidth, stdata_->imDisp);
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_16SC1, stdata_->imHeight, stdata_->imWidth, 2 * stdata_->imWidth, stdata_->imDisp);
img_.header.stamp = raw_stereo_.header.stamp;
img_.header.frame_id = raw_stereo_.header.frame_id;
@@ -277,7 +277,7 @@
{
if (img_data->imRawType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1, img_data->imHeight, img_data->imWidth, img_data->imWidth, img_data->imRaw);
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1, img_data->imHeight, img_data->imWidth, img_data->imWidth, img_data->imRaw);
img_.header.stamp = raw_stereo_.header.stamp;
img_.header.frame_id = raw_stereo_.header.frame_id;
@@ -287,7 +287,7 @@
if (img_data->imType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1,
img_data->imHeight, img_data->imWidth, 2 * img_data->imWidth,
img_data->im);
img_.header.stamp = raw_stereo_.header.stamp;
@@ -297,7 +297,7 @@
if (img_data->imColorType != COLOR_CODING_NONE && img_data->imColorType == COLOR_CODING_RGB8)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC3,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC3,
img_data->imHeight, img_data->imWidth, 3 * img_data->imWidth,
img_data->imColor );
@@ -308,7 +308,7 @@
if (img_data->imRectType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1,
img_data->imHeight, img_data->imWidth, img_data->imWidth,
img_data->imRect );
img_.header.stamp = raw_stereo_.header.stamp;
@@ -318,7 +318,7 @@
if (img_data->imRectColorType != COLOR_CODING_NONE && img_data->imRectColorType == COLOR_CODING_RGB8)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC3,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC3,
img_data->imHeight, img_data->imWidth, 3 * img_data->imWidth,
img_data->imRectColor);
img_.header.stamp = raw_stereo_.header.stamp;
@@ -328,7 +328,7 @@
if (img_data->imRectColorType != COLOR_CODING_NONE && img_data->imRectColorType == COLOR_CODING_RGBA8)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC4,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC4,
img_data->imHeight, img_data->imWidth, 4 * img_data->imWidth,
img_data->imRectColor );
img_.header.stamp = raw_stereo_.header.stamp;
Modified: pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_calibration.cpp
===================================================================
--- pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_calibration.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_calibration.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -136,7 +136,7 @@
private:
void image_cb()
{
- if( !_cvbridge.fromImage(_imagemsg, "mono") ) {
+ if( !_cvbridge.fromImage(_imagemsg, "mono8") ) {
ROS_ERROR("failed to get image");
return;
}
Modified: pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_detector.cpp
===================================================================
--- pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_detector.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_detector.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -200,7 +200,7 @@
return;
}
- if( !_cvbridge.fromImage(_imagemsg, "mono") ) {
+ if( !_cvbridge.fromImage(_imagemsg, "mono8") ) {
ROS_ERROR("failed to get image");
return;
}
Modified: pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting.cpp
===================================================================
--- pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -1169,14 +1169,14 @@
{
boost::lock_guard<boost::mutex> lock(cv_mutex);
- if (lbridge.fromImage(limage, "bgr"))
+ if (lbridge.fromImage(limage, "bgr8"))
{
if(left != NULL)
cvReleaseImage(&left);
left = cvCloneImage(lbridge.toIpl());
}
-// if (rbridge.fromImage(rimage, "bgr"))
+// if (rbridge.fromImage(rimage, "bgr8"))
// {
// if(right != NULL)
// cvReleaseImage(&right);
Modified: pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting2.cpp
===================================================================
--- pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting2.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting2.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -318,7 +318,7 @@
boost::unique_lock<boost::mutex> lock(data_lock_);
limage_ = image;
- if(lbridge_.fromImage(*limage_, "bgr")) {
+ if(lbridge_.fromImage(*limage_, "bgr8")) {
left_ = lbridge_.toIpl();
}
}
Modified: pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_tracker.cpp
===================================================================
--- pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_tracker.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_tracker.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -25,7 +25,7 @@
bool OutletTracker::detectObject(tf::Transform &pose)
{
- if (!img_bridge_.fromImage(img_, "bgr")) {
+ if (!img_bridge_.fromImage(img_, "bgr8")) {
ROS_ERROR("Failed to convert image");
return false;
}
Modified: pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/plug_tracker.cpp
===================================================================
--- pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/plug_tracker.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/plug_tracker.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -82,7 +82,7 @@
bool PlugTracker::detectObject(tf::Transform &pose)
{
- if (!img_bridge_.fromImage(img_, "mono")) {
+ if (!img_bridge_.fromImage(img_, "mono8")) {
ROS_ERROR("Failed to convert image");
return false; // throw instead?
}
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -94,21 +94,32 @@
Ogre::PixelFormat format = Ogre::PF_R8G8B8;
- if (image->type == sensor_msgs::Image::TYPE_8UC4)
+ if (image->encoding == sensor_msgs::image_encodings::RGB8)
{
+ format = Ogre::PF_R8G8B8;
+ }
+ else if (image->encoding == sensor_msgs::image_encodings::RGBA8)
+ {
+ format = Ogre::PF_R8G8B8A8;
+ }
+ else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC4 ||
+ image->encoding == sensor_msgs::image_encodings::BGRA8)
+ {
format = Ogre::PF_B8G8R8A8;
}
- else if (image->type == sensor_msgs::Image::TYPE_8UC3)
+ else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC3 ||
+ image->encoding == sensor_msgs::image_encodings::BGR8)
{
format = Ogre::PF_B8G8R8;
}
- else if (image->type == sensor_msgs::Image::TYPE_8UC1)
+ else if (image->encoding == sensor_msgs::image_encodings::TYPE_8UC1 ||
+ image->encoding == sensor_msgs::image_encodings::MONO8)
{
format = Ogre::PF_L8;
}
else
{
- ROS_ERROR("Unsupported image encoding [%d]", image->type);
+ ROS_ERROR("Unsupported image encoding [%s]", image->encoding.c_str());
return false;
}
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.h 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.h 2009-08-09 19:14:00 UTC (rev 21244)
@@ -31,6 +31,8 @@
#define RVIZ_ROS_IMAGE_TEXTURE_H
#include <sensor_msgs/Image.h>
+#include "sensor_msgs/image_encodings.h"
+
#include <OGRE/OgreTexture.h>
#include <boost/shared_ptr.hpp>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|