|
From: <jl...@us...> - 2009-08-10 08:53:23
|
Revision: 21364
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21364&view=rev
Author: jleibs
Date: 2009-08-10 08:53:09 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
Migration of RawStereo message.
Modified Paths:
--------------
pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr
pkg/trunk/stacks/stereo/stereo_msgs/manifest.xml
pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr 2009-08-10 08:46:24 UTC (rev 21363)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr 2009-08-10 08:53:09 UTC (rev 21364)
@@ -315,6 +315,9 @@
valid = True
+ def update_empty(self, old_msg, new_msg):
+ pass
+
def update_mono_uint8(self, old_msg, new_msg):
assert (len(old_msg.uint8_data.layout.dim) == 3 and
old_msg.uint8_data.layout.dim[0].label == 'height' and
@@ -361,7 +364,8 @@
new_msg.is_bigendian = 0
def update(self, old_msg, new_msg):
- encoding_map = {('mono', 'uint8'): self.update_mono_uint8,
+ encoding_map = {('',''): self.update_empty,
+ ('mono', 'uint8'): self.update_mono_uint8,
('rgb', 'uint8'): self.update_rgb_uint8,
('bgr', 'uint8'): self.update_bgr_uint8}
key = (old_msg.encoding, old_msg.depth)
Modified: pkg/trunk/stacks/stereo/stereo_msgs/manifest.xml
===================================================================
--- pkg/trunk/stacks/stereo/stereo_msgs/manifest.xml 2009-08-10 08:46:24 UTC (rev 21363)
+++ pkg/trunk/stacks/stereo/stereo_msgs/manifest.xml 2009-08-10 08:53:09 UTC (rev 21364)
@@ -9,9 +9,12 @@
<review status="unreviewed" notes=""/>
<url>http://pr.willowgarage.com/wiki/stereo_msgs</url>
<depend package="sensor_msgs"/>
+ <depend package="rosbagmigration"/>
<export>
<cpp cflags="-I${prefix}/msg/cpp"/>
+ <rosbagmigration rule_file="migration_rules/stereo_msgs.bmr"/>
</export>
+
</package>
Modified: pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py
===================================================================
--- pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py 2009-08-10 08:46:24 UTC (rev 21363)
+++ pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py 2009-08-10 08:53:09 UTC (rev 21364)
@@ -172,12 +172,11 @@
def get_new_raw_stereo(self):
from stereo_msgs.msg import RawStereo
from stereo_msgs.msg import StereoInfo
- from stereo_msgs.msg import CamInfo
+ from stereo_msgs.msg import DisparityInfo
+ from sensor_msgs.msg import CameraInfo
from sensor_msgs.msg import RegionOfInterest
from sensor_msgs.msg import Image
- from sensor_msgs.msg import DisparityInfo
-
import random
r = random.Random(5678)
@@ -206,7 +205,7 @@
0.0, 1.0, 0.0, -240.53899000000001,
0.0, 0.0, 0.0, 722.28197999999998,
0.0, 0.0, 11.262630896461046, -0.0)),
- CamInfo(None,
+ CameraInfo(None,
480, 640,
RegionOfInterest(0,0,480,640),
(-0.45795000000000002, 0.29532999999999998, 0.0, 0.0, 0.0),
@@ -221,7 +220,7 @@
0.0, 0.0, 1.0, 0.0)),
RawStereo.IMAGE,
left_img,
- CamInfo(None,
+ CameraInfo(None,
480, 640,
RegionOfInterest(0,0,480,640),
(-0.46471000000000001, 0.28405999999999998, 0.0, 0.0, 0.0),
@@ -297,10 +296,10 @@
m.deserialize(buff.getvalue())
#Compare
- print "old"
- print roslib.message.strify_message(msgs[0][1])
- print "new"
- print roslib.message.strify_message(m)
+# print "old"
+# print roslib.message.strify_message(msgs[0][1])
+# print "new"
+# print roslib.message.strify_message(m)
# Strifying them helps make the comparison easier until I figure out why the equality operator is failing
self.assertTrue(roslib.message.strify_message(msgs[0][1]) == roslib.message.strify_message(m))
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|