|
From: <jam...@us...> - 2009-08-08 06:38:18
|
Revision: 21165
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21165&view=rev
Author: jamesbowman
Date: 2009-08-08 06:38:06 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
Rename rows,cols to height,width in Image message
Modified Paths:
--------------
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg
pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h
pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py
pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp
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-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-08 06:38:06 UTC (rev 21165)
@@ -544,8 +544,8 @@
static void setBgrLayout(sensor_msgs::Image &image, int width, int height)
{
image.type = sensor_msgs::Image::TYPE_8UC3;
- image.rows = height;
- image.cols = width;
+ image.height = height;
+ image.width = width;
image.step = width * 3;
image.data.resize(height * (width * 3));
}
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h 2009-08-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h 2009-08-08 06:38:06 UTC (rev 21165)
@@ -48,8 +48,8 @@
void* data_arg)
{
image.type = type_arg;
- image.rows = rows_arg;
- image.cols = cols_arg;
+ image.height = rows_arg;
+ image.width = cols_arg;
image.step = step_arg;
size_t st0 = (step_arg * rows_arg);
image.data.resize(st0);
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg 2009-08-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg 2009-08-08 06:38:06 UTC (rev 21165)
@@ -1,37 +1,41 @@
Header header # Header
-int32 TYPE_8UC1=0
-int32 TYPE_8UC2=8
-int32 TYPE_8UC3=16
-int32 TYPE_8UC4=24
-int32 TYPE_8SC1=1
-int32 TYPE_8SC2=9
-int32 TYPE_8SC3=17
-int32 TYPE_8SC4=25
-int32 TYPE_16UC1=2
-int32 TYPE_16UC2=10
-int32 TYPE_16UC3=18
-int32 TYPE_16UC4=26
-int32 TYPE_16SC1=3
-int32 TYPE_16SC2=11
-int32 TYPE_16SC3=19
-int32 TYPE_16SC4=27
-int32 TYPE_32SC1=4
-int32 TYPE_32SC2=12
-int32 TYPE_32SC3=20
-int32 TYPE_32SC4=28
-int32 TYPE_32FC1=5
-int32 TYPE_32FC2=13
-int32 TYPE_32FC3=21
-int32 TYPE_32FC4=29
-int32 TYPE_64FC1=6
-int32 TYPE_64FC2=14
-int32 TYPE_64FC3=22
-int32 TYPE_64FC4=30
+# These are the two most popular image types, so make special synonyms for them
+uint32 TYPE_MONO8=0
+uint32 TYPE_BGR8=16
-int32 type # Type of elements, and channels. Encoded as in OpenCV's TYPE_8UC1 .. TYPE_64FC4.
-int32 step # Full row length in bytes
+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.
+uint32 step # Full row length in bytes
uint8[] data # actual matrix data, size is (step * rows)
-int32 rows # Number of rows
-int32 cols # Number of columns
+uint32 height # image height, that is, number of rows
+uint32 width # image width, that is, number of columns
uint8 is_bigendian # is this data bigendian
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-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h 2009-08-08 06:38:06 UTC (rev 21165)
@@ -101,7 +101,7 @@
{
CvMat cvmHeader;
- cvInitMatHeader(&cvmHeader, rosimg.rows, rosimg.cols, rosimg.type, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
+ cvInitMatHeader(&cvmHeader, rosimg.height, rosimg.width, rosimg.type, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
cvGetImage(&cvmHeader, rosimg_);
// cvSetData(rosimg_, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
@@ -147,11 +147,11 @@
cvm = cvGetMat(source, &header);
dest.type = cvm->type & (CV_MAT_TYPE_MASK | CV_MAT_DEPTH_MASK);
- dest.cols = cvm->cols;
- dest.rows = cvm->rows;
+ dest.width = cvm->width;
+ dest.height = cvm->height;
dest.step = cvm->step;
- dest.data.resize(cvm->step * cvm->rows);
- memcpy((char*)(&dest.data[0]), source->imageData, cvm->step * cvm->rows);
+ dest.data.resize(cvm->step * cvm->height);
+ memcpy((char*)(&dest.data[0]), source->imageData, cvm->step * cvm->height);
return true;
}
};
Modified: pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py 2009-08-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py 2009-08-08 06:38:06 UTC (rev 21165)
@@ -69,8 +69,8 @@
ball_yv = -ball_yv
img_msg = sensor_msgs.msg.Image()
- img_msg.rows = 480
- img_msg.cols = 640
+ img_msg.width = 640
+ img_msg.height = 480
img_msg.type = cv.CV_8UC1
img_msg.step = 640
img_msg.data = cvim.tostring()
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-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h 2009-08-08 06:38:06 UTC (rev 21165)
@@ -211,8 +211,8 @@
// 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) {
- im->imHeight = im_msg.rows;
- im->imWidth = im_msg.cols;
+ im->imHeight = im_msg.height;
+ im->imWidth = im_msg.width;
} else {
im->imHeight = info_msg.height;
im->imWidth = info_msg.width;
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-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp 2009-08-08 06:38:06 UTC (rev 21165)
@@ -112,10 +112,10 @@
return false;
}
- width_ = image->cols;
- height_ = image->rows;
+ width_ = image->width;
+ height_ = image->height;
- uint32_t size = image->rows * image->step;
+ uint32_t size = image->height * image->step;
Ogre::DataStreamPtr pixel_stream;
pixel_stream.bind(new Ogre::MemoryDataStream((void*)(&image->data[0]), size));
texture_->unload();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|