$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of Willow Garage, Inc. nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 # 00034 00035 import roslib 00036 roslib.load_manifest('test_common_msgs') 00037 00038 import sys 00039 import struct 00040 00041 import unittest 00042 00043 import rostest 00044 import rosbag 00045 00046 import re 00047 from cStringIO import StringIO 00048 import os 00049 00050 import rospy 00051 00052 import math 00053 00054 def quaternion_from_euler(x, y, z): 00055 x /= 2.0 00056 y /= 2.0 00057 z /= 2.0 00058 ci = math.cos(x) 00059 si = math.sin(x) 00060 cj = math.cos(y) 00061 sj = math.sin(y) 00062 ck = math.cos(z) 00063 sk = math.sin(z) 00064 cc = ci*ck 00065 cs = ci*sk 00066 sc = si*ck 00067 ss = si*sk 00068 00069 quaternion = [0.0,0.0,0.0,0.0] 00070 00071 quaternion[0] = cj*sc - sj*cs 00072 quaternion[1] = cj*ss + sj*cc 00073 quaternion[2] = cj*cs - sj*sc 00074 quaternion[3] = cj*cc + sj*ss 00075 00076 return quaternion 00077 00078 migrator = rosbag.migration.MessageMigrator() 00079 00080 identity6x6 = [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] 00081 00082 00083 def repack(x): 00084 return struct.unpack('<f',struct.pack('<f',x))[0] 00085 00086 class TestCommonMsgsMigration(unittest.TestCase): 00087 00088 00089 # (*) Acceleration.saved 00090 # (*) AngularAcceleration.saved 00091 # (*) AngularVelocity.saved 00092 # (*) BatteryState.saved 00093 # (*) ChannelFloat32.saved 00094 # (*) DiagnosticMessage.saved 00095 # (*) DiagnosticStatus.saved 00096 # (*) Path.saved 00097 # (*) Point32.saved 00098 # (*) PointCloud.saved 00099 # (*) Point.saved 00100 # (*) PointStamped.saved 00101 # (*) Polygon3D.saved 00102 # (*) PoseDDot.saved 00103 # (*) Pose.saved 00104 # (*) PoseStamped.saved 00105 # (*) PoseWithCovariance.saved 00106 # (*) Quaternion.saved 00107 # (*) QuaternionStamped.saved 00108 # (*) Transform.saved 00109 # (*) TransformStamped.saved 00110 # ( ) TransformStamped_parent_id.saved 00111 # (*) Twist.saved 00112 # (*) Vector3.saved 00113 # (*) Vector3Stamped.saved 00114 # (*) Velocity.saved 00115 # (*) Wrench.saved 00116 # (*) DiagnosticString.saved 00117 # (*) DiagnosticValue.saved 00118 # (*) OccupancyGrid.saved 00119 # (*) VOPose.saved 00120 # (*) RobotBase2DOdom.saved 00121 00122 00123 ########### CamInfo ############### 00124 00125 def get_old_cam_info(self): 00126 cam_info_classes = self.load_saved_classes('CamInfo.saved') 00127 00128 cam_info = cam_info_classes['image_msgs/CamInfo'] 00129 00130 return cam_info(None, 00131 480, 640, 00132 (-0.45795000000000002, 0.29532999999999998, 0.0, 0.0, 0.0), 00133 (734.37707999999998, 0.0, 343.25992000000002, 00134 0.0, 734.37707999999998, 229.65119999999999, 00135 0.0, 0.0, 1.0), 00136 (0.99997999999999998, 0.0012800000000000001, -0.0057400000000000003, 00137 -0.0012700000000000001, 1.0, 0.00148, 00138 0.0057400000000000003, -0.00147, 0.99997999999999998), 00139 (722.28197999999998, 0.0, 309.70123000000001, 0.0, 00140 0.0, 722.28197999999998, 240.53899000000001, 0.0, 00141 0.0, 0.0, 1.0, 0.0)) 00142 00143 def get_new_cam_info(self): 00144 from sensor_msgs.msg import CameraInfo 00145 from sensor_msgs.msg import RegionOfInterest 00146 00147 return CameraInfo(None, 00148 480, 640, 00149 "plumb_bob", 00150 (-0.45795000000000002, 0.29532999999999998, 0.0, 0.0, 0.0), 00151 (734.37707999999998, 0.0, 343.25992000000002, 00152 0.0, 734.37707999999998, 229.65119999999999, 00153 0.0, 0.0, 1.0), 00154 (0.99997999999999998, 0.0012800000000000001, -0.0057400000000000003, 00155 -0.0012700000000000001, 1.0, 0.00148, 00156 0.0057400000000000003, -0.00147, 0.99997999999999998), 00157 (722.28197999999998, 0.0, 309.70123000000001, 0.0, 00158 0.0, 722.28197999999998, 240.53899000000001, 0.0, 00159 0.0, 0.0, 1.0, 0.0), 00160 1, 1, 00161 RegionOfInterest(0,0,480,640,False)) 00162 00163 def test_cam_info(self): 00164 self.do_test('cam_info', self.get_old_cam_info, self.get_new_cam_info) 00165 00166 00167 00168 00169 ########### CameraInfo ############### 00170 00171 def get_old_camera_info(self): 00172 camera_info_classes = self.load_saved_classes('CameraInfo.saved') 00173 00174 camera_info = camera_info_classes['sensor_msgs/CameraInfo'] 00175 region_of_interest = camera_info_classes['sensor_msgs/RegionOfInterest'] 00176 00177 return camera_info(None, 00178 480, 640, 00179 region_of_interest(0,0,480,640), 00180 (-0.45795000000000002, 0.29532999999999998, 0.0, 0.0, 0.0), 00181 (734.37707999999998, 0.0, 343.25992000000002, 00182 0.0, 734.37707999999998, 229.65119999999999, 00183 0.0, 0.0, 1.0), 00184 (0.99997999999999998, 0.0012800000000000001, -0.0057400000000000003, 00185 -0.0012700000000000001, 1.0, 0.00148, 00186 0.0057400000000000003, -0.00147, 0.99997999999999998), 00187 (722.28197999999998, 0.0, 309.70123000000001, 0.0, 00188 0.0, 722.28197999999998, 240.53899000000001, 0.0, 00189 0.0, 0.0, 1.0, 0.0)) 00190 00191 def get_new_camera_info(self): 00192 from sensor_msgs.msg import CameraInfo 00193 from sensor_msgs.msg import RegionOfInterest 00194 00195 return CameraInfo(None, 00196 480, 640, 00197 "plumb_bob", 00198 (-0.45795000000000002, 0.29532999999999998, 0.0, 0.0, 0.0), 00199 (734.37707999999998, 0.0, 343.25992000000002, 00200 0.0, 734.37707999999998, 229.65119999999999, 00201 0.0, 0.0, 1.0), 00202 (0.99997999999999998, 0.0012800000000000001, -0.0057400000000000003, 00203 -0.0012700000000000001, 1.0, 0.00148, 00204 0.0057400000000000003, -0.00147, 0.99997999999999998), 00205 (722.28197999999998, 0.0, 309.70123000000001, 0.0, 00206 0.0, 722.28197999999998, 240.53899000000001, 0.0, 00207 0.0, 0.0, 1.0, 0.0), 00208 1, 1, 00209 RegionOfInterest(0,0,480,640,False)) 00210 00211 def test_camera_info(self): 00212 self.do_test('camera_info', self.get_old_camera_info, self.get_new_camera_info) 00213 00214 00215 00216 00217 ########### CompressedImage ############### 00218 00219 def get_old_compressed_image(self): 00220 compressed_image_classes = self.load_saved_classes('CompressedImage.saved') 00221 00222 compressed_image = compressed_image_classes['sensor_msgs/CompressedImage'] 00223 00224 multi_array_layout = compressed_image_classes['std_msgs/MultiArrayLayout'] 00225 multi_array_dimension = compressed_image_classes['std_msgs/MultiArrayDimension'] 00226 uint8_multi_array = compressed_image_classes['std_msgs/UInt8MultiArray'] 00227 00228 import random 00229 r = random.Random(1234) 00230 00231 # This is not a jpeg, but we don't really care. It's just a binary blob. 00232 return compressed_image(None, 00233 'image', 00234 'mono', 00235 'jpeg', 00236 uint8_multi_array(multi_array_layout([multi_array_dimension('data', 1000, 1000)], 0), 00237 [r.randint(0,255) for x in xrange(0,1000)])) 00238 00239 def get_new_compressed_image(self): 00240 from sensor_msgs.msg import CompressedImage 00241 00242 import random 00243 r = random.Random(1234) 00244 00245 return CompressedImage(None, 00246 "jpeg", 00247 [r.randint(0,255) for x in xrange(0,1000)]) 00248 00249 def test_compressed_image(self): 00250 self.do_test('compressed_image', self.get_old_compressed_image, self.get_new_compressed_image) 00251 00252 00253 00254 00255 ########### Image ############### 00256 00257 def get_old_mono_image(self): 00258 image_classes = self.load_saved_classes('Image.saved') 00259 00260 image = image_classes['image_msgs/Image'] 00261 00262 multi_array_layout = image_classes['std_msgs/MultiArrayLayout'] 00263 multi_array_dimension = image_classes['std_msgs/MultiArrayDimension'] 00264 00265 uint8_multi_array = image_classes['std_msgs/UInt8MultiArray'] 00266 int8_multi_array = image_classes['std_msgs/Int8MultiArray'] 00267 uint16_multi_array = image_classes['std_msgs/UInt16MultiArray'] 00268 int16_multi_array = image_classes['std_msgs/Int16MultiArray'] 00269 uint32_multi_array = image_classes['std_msgs/UInt32MultiArray'] 00270 int32_multi_array = image_classes['std_msgs/Int32MultiArray'] 00271 uint64_multi_array = image_classes['std_msgs/UInt64MultiArray'] 00272 int64_multi_array = image_classes['std_msgs/Int64MultiArray'] 00273 00274 float32_multi_array = image_classes['std_msgs/Float32MultiArray'] 00275 float64_multi_array = image_classes['std_msgs/Float64MultiArray'] 00276 00277 import random 00278 r = random.Random(1234) 00279 00280 return image(None, 00281 'image', 00282 'mono', 00283 'uint8', 00284 uint8_multi_array(multi_array_layout([multi_array_dimension('height', 480, 307200), 00285 multi_array_dimension('width', 640, 640), 00286 multi_array_dimension('channel', 1, 1) 00287 ], 0), 00288 [r.randint(0,255) for x in xrange(0,307200)]), 00289 int8_multi_array(), 00290 uint16_multi_array(), 00291 int16_multi_array(), 00292 uint32_multi_array(), 00293 int32_multi_array(), 00294 uint64_multi_array(), 00295 int64_multi_array(), 00296 float32_multi_array(), 00297 float64_multi_array()) 00298 00299 def get_new_mono_image(self): 00300 from sensor_msgs.msg import Image 00301 00302 import random 00303 r = random.Random(1234) 00304 00305 return Image(None, 00306 480, 00307 640, 00308 'mono8', 00309 0, 00310 640, 00311 [r.randint(0,255) for x in xrange(0,307200)]) 00312 00313 def test_mono_image(self): 00314 self.do_test('mono_image', self.get_old_mono_image, self.get_new_mono_image) 00315 00316 00317 def get_old_rgb_image(self): 00318 image_classes = self.load_saved_classes('Image.saved') 00319 00320 image = image_classes['image_msgs/Image'] 00321 00322 multi_array_layout = image_classes['std_msgs/MultiArrayLayout'] 00323 multi_array_dimension = image_classes['std_msgs/MultiArrayDimension'] 00324 00325 uint8_multi_array = image_classes['std_msgs/UInt8MultiArray'] 00326 int8_multi_array = image_classes['std_msgs/Int8MultiArray'] 00327 uint16_multi_array = image_classes['std_msgs/UInt16MultiArray'] 00328 int16_multi_array = image_classes['std_msgs/Int16MultiArray'] 00329 uint32_multi_array = image_classes['std_msgs/UInt32MultiArray'] 00330 int32_multi_array = image_classes['std_msgs/Int32MultiArray'] 00331 uint64_multi_array = image_classes['std_msgs/UInt64MultiArray'] 00332 int64_multi_array = image_classes['std_msgs/Int64MultiArray'] 00333 00334 float32_multi_array = image_classes['std_msgs/Float32MultiArray'] 00335 float64_multi_array = image_classes['std_msgs/Float64MultiArray'] 00336 00337 import random 00338 r = random.Random(1234) 00339 00340 return image(None, 00341 'image', 00342 'rgb', 00343 'uint8', 00344 uint8_multi_array(multi_array_layout([multi_array_dimension('height', 480, 921600), 00345 multi_array_dimension('width', 640, 1920), 00346 multi_array_dimension('channel', 3, 3) 00347 ], 0), 00348 [r.randint(0,255) for x in xrange(0,921600)]), 00349 int8_multi_array(), 00350 uint16_multi_array(), 00351 int16_multi_array(), 00352 uint32_multi_array(), 00353 int32_multi_array(), 00354 uint64_multi_array(), 00355 int64_multi_array(), 00356 float32_multi_array(), 00357 float64_multi_array()) 00358 00359 def get_new_rgb_image(self): 00360 from sensor_msgs.msg import Image 00361 00362 import random 00363 r = random.Random(1234) 00364 00365 return Image(None, 00366 480, 00367 640, 00368 'rgb8', 00369 0, 00370 1920, 00371 [r.randint(0,255) for x in xrange(0,921600)]) 00372 00373 def test_rgb_image(self): 00374 self.do_test('rgb_image', self.get_old_rgb_image, self.get_new_rgb_image) 00375 00376 00377 00378 ########### RobotBase2DOdom ############### 00379 00380 def get_old_robot_base_2d_odom(self): 00381 robot_base_2d_odom_classes = self.load_saved_classes('RobotBase2DOdom.saved') 00382 00383 robot_base_2d_odom = robot_base_2d_odom_classes['deprecated_msgs/RobotBase2DOdom'] 00384 pose_2d_float32 = robot_base_2d_odom_classes['deprecated_msgs/Pose2DFloat32'] 00385 00386 return robot_base_2d_odom(None, pose_2d_float32(3.33, 2.22, 1.11), pose_2d_float32(.1,.2,.3), 0, 1) 00387 00388 def get_new_robot_base_2d_odom(self): 00389 from nav_msgs.msg import Odometry 00390 from geometry_msgs.msg import PoseWithCovariance 00391 from geometry_msgs.msg import Pose 00392 from geometry_msgs.msg import Point 00393 from geometry_msgs.msg import Quaternion 00394 from geometry_msgs.msg import TwistWithCovariance 00395 from geometry_msgs.msg import Twist 00396 from geometry_msgs.msg import Vector3 00397 00398 # We have to repack x,y values because they moved from float to double 00399 p = PoseWithCovariance(Pose(Point(repack(3.33), repack(2.22), 0), apply(Quaternion,quaternion_from_euler(0,0,repack(1.11)))), 36*[0.]) 00400 t = TwistWithCovariance(Twist(Vector3(repack(.1), repack(.2), 0), Vector3(0, 0, repack(.3))), 36*[0.]) 00401 00402 return Odometry(None, 'base_footprint', p, t) 00403 00404 def test_robot_base_2d_odom(self): 00405 self.do_test('robot_base_2d_odom', self.get_old_robot_base_2d_odom, self.get_new_robot_base_2d_odom) 00406 00407 00408 00409 00410 ########### OccupancyGrid ############### 00411 00412 def get_old_occupancy_grid(self): 00413 occupancy_grid_classes = self.load_saved_classes('OccGrid.saved') 00414 00415 occupancy_grid = occupancy_grid_classes['robot_msgs/OccGrid'] 00416 map_meta_data = occupancy_grid_classes['robot_msgs/MapMetaData'] 00417 pose = occupancy_grid_classes['robot_msgs/Pose'] 00418 point = occupancy_grid_classes['robot_msgs/Point'] 00419 quaternion = occupancy_grid_classes['robot_msgs/Quaternion'] 00420 00421 import random 00422 r = random.Random(1234) 00423 00424 return occupancy_grid(map_meta_data(rospy.Time(123,456), 0.1, 100, 100, pose(point(1.23, 4.56, 7.89), quaternion(0,0,0,1))), [r.randint(-1,100) for x in xrange(0,1000)]) 00425 00426 def get_new_occupancy_grid(self): 00427 from nav_msgs.msg import OccupancyGrid 00428 from nav_msgs.msg import MapMetaData 00429 from std_msgs.msg import Header 00430 from geometry_msgs.msg import Pose 00431 from geometry_msgs.msg import Point 00432 from geometry_msgs.msg import Quaternion 00433 00434 import random 00435 r = random.Random(1234) 00436 00437 return OccupancyGrid(Header(0, rospy.Time(0,0), "/map"), MapMetaData(rospy.Time(123,456), 0.1, 100, 100, Pose(Point(1.23, 4.56, 7.89), Quaternion(0,0,0,1))), [r.randint(-1,100) for x in xrange(0,1000)]) 00438 00439 def test_occupancy_grid(self): 00440 self.do_test('occupancy_grid', self.get_old_occupancy_grid, self.get_new_occupancy_grid) 00441 00442 00443 ########### Polygon3d ############### 00444 00445 def get_old_polygon3d(self): 00446 polygon3d_classes = self.load_saved_classes('Polygon3D.saved') 00447 00448 polygon3d = polygon3d_classes['robot_msgs/Polygon3D'] 00449 point32 = polygon3d_classes['robot_msgs/Point32'] 00450 color_rgba = polygon3d_classes['std_msgs/ColorRGBA'] 00451 00452 return polygon3d([point32(1.23, 4.56, 7.89), point32(82.861, 31.028, 93.317), point32(87.569, 29.085, 33.415)], color_rgba(255, 100, 100, 0)) 00453 00454 def get_new_polygon3d(self): 00455 from geometry_msgs.msg import Polygon 00456 from geometry_msgs.msg import Point32 00457 00458 return Polygon([Point32(1.23, 4.56, 7.89), Point32(82.861, 31.028, 93.317), Point32(87.569, 29.085, 33.415)]) 00459 00460 def test_polygon3d(self): 00461 self.do_test('polygon3d', self.get_old_polygon3d, self.get_new_polygon3d) 00462 00463 00464 ########### Acceleration ############### 00465 00466 def get_old_acceleration(self): 00467 acceleration_classes = self.load_saved_classes('Acceleration.saved') 00468 00469 acceleration = acceleration_classes['robot_msgs/Acceleration'] 00470 00471 return acceleration(1.23, 4.56, 7.89) 00472 00473 def get_new_acceleration(self): 00474 from geometry_msgs.msg import Vector3 00475 00476 return Vector3(1.23, 4.56, 7.89) 00477 00478 def test_acceleration(self): 00479 self.do_test('acceleration', self.get_old_acceleration, self.get_new_acceleration) 00480 00481 00482 00483 ########### AngularAcceleration ############### 00484 00485 def get_old_angular_acceleration(self): 00486 angular_acceleration_classes = self.load_saved_classes('AngularAcceleration.saved') 00487 00488 angular_acceleration = angular_acceleration_classes['robot_msgs/AngularAcceleration'] 00489 00490 return angular_acceleration(1.23, 4.56, 7.89) 00491 00492 def get_new_angular_acceleration(self): 00493 from geometry_msgs.msg import Vector3 00494 00495 return Vector3(1.23, 4.56, 7.89) 00496 00497 def test_angular_acceleration(self): 00498 self.do_test('angular_acceleration', self.get_old_angular_acceleration, self.get_new_angular_acceleration) 00499 00500 00501 ########### DiagnosticValue ############### 00502 00503 def get_old_diagnostic_value(self): 00504 diagnostic_value_classes = self.load_saved_classes('DiagnosticValue.saved') 00505 00506 diagnostic_value = diagnostic_value_classes['diagnostic_msgs/DiagnosticValue'] 00507 00508 return diagnostic_value(42.42, 'foo') 00509 00510 def get_new_diagnostic_value(self): 00511 from diagnostic_msgs.msg import KeyValue 00512 00513 return KeyValue('foo', str(repack(42.42))) 00514 00515 00516 def test_diagnostic_value(self): 00517 self.do_test('diagnostic_value', self.get_old_diagnostic_value, self.get_new_diagnostic_value) 00518 00519 00520 ########### DiagnosticString ############### 00521 00522 def get_old_diagnostic_string(self): 00523 diagnostic_string_classes = self.load_saved_classes('DiagnosticString.saved') 00524 00525 diagnostic_string = diagnostic_string_classes['diagnostic_msgs/DiagnosticString'] 00526 00527 return diagnostic_string('xxxxx', 'bar') 00528 00529 def get_new_diagnostic_string(self): 00530 from diagnostic_msgs.msg import KeyValue 00531 00532 return KeyValue('bar', 'xxxxx') 00533 00534 00535 def test_diagnostic_string(self): 00536 self.do_test('diagnostic_string', self.get_old_diagnostic_string, self.get_new_diagnostic_string) 00537 00538 00539 ########### DiagnosticStatus ############### 00540 00541 def get_old_diagnostic_status(self): 00542 diagnostic_status_classes = self.load_saved_classes('DiagnosticStatus.saved') 00543 00544 diagnostic_status = diagnostic_status_classes['diagnostic_msgs/DiagnosticStatus'] 00545 diagnostic_value = diagnostic_status_classes['diagnostic_msgs/DiagnosticValue'] 00546 diagnostic_string = diagnostic_status_classes['diagnostic_msgs/DiagnosticString'] 00547 00548 return diagnostic_status(0, "abcdef", "ghijkl", [diagnostic_value(42.42, 'foo')], [diagnostic_string('xxxxx', 'bar')]) 00549 00550 def get_new_diagnostic_status(self): 00551 from diagnostic_msgs.msg import DiagnosticStatus 00552 from diagnostic_msgs.msg import KeyValue 00553 00554 return DiagnosticStatus(0, "abcdef", "ghijkl", "NONE", [KeyValue('foo', str(repack(42.42))), KeyValue('bar', 'xxxxx')]) 00555 00556 00557 def test_diagnostic_status(self): 00558 self.do_test('diagnostic_status', self.get_old_diagnostic_status, self.get_new_diagnostic_status) 00559 00560 00561 ########### DiagnosticMessage ############### 00562 00563 def get_old_diagnostic_message(self): 00564 diagnostic_message_classes = self.load_saved_classes('DiagnosticMessage.saved') 00565 00566 diagnostic_message = diagnostic_message_classes['diagnostic_msgs/DiagnosticMessage'] 00567 diagnostic_status = diagnostic_message_classes['diagnostic_msgs/DiagnosticStatus'] 00568 diagnostic_value = diagnostic_message_classes['diagnostic_msgs/DiagnosticValue'] 00569 diagnostic_string = diagnostic_message_classes['diagnostic_msgs/DiagnosticString'] 00570 00571 msg = diagnostic_message(None, []) 00572 msg.status.append(diagnostic_status(0, "abcdef", "ghijkl", [diagnostic_value(12.34, 'abc')], [diagnostic_string('ghbvf', 'jkl')])) 00573 msg.status.append(diagnostic_status(0, "mnop", "qrst", [diagnostic_value(56.78, 'def')], [diagnostic_string('klmnh', 'mno')])) 00574 msg.status.append(diagnostic_status(0, "uvw", "xyz", [diagnostic_value(90.12, 'ghi')], [diagnostic_string('erfcd', 'pqr')])) 00575 00576 return msg 00577 00578 def get_new_diagnostic_message(self): 00579 from diagnostic_msgs.msg import DiagnosticArray 00580 from diagnostic_msgs.msg import DiagnosticStatus 00581 from diagnostic_msgs.msg import KeyValue 00582 00583 msg = DiagnosticArray(None, []) 00584 msg.status.append(DiagnosticStatus(0, "abcdef", "ghijkl", "NONE", [KeyValue('abc', str(repack(12.34))), KeyValue('jkl', 'ghbvf')])) 00585 msg.status.append(DiagnosticStatus(0, "mnop", "qrst", "NONE", [KeyValue('def', str(repack(56.78))), KeyValue('mno', 'klmnh')])) 00586 msg.status.append(DiagnosticStatus(0, "uvw", "xyz", "NONE", [KeyValue('ghi', str(repack(90.12))), KeyValue('pqr', 'erfcd')])) 00587 00588 return msg 00589 00590 00591 def test_diagnostic_message(self): 00592 self.do_test('diagnostic_message', self.get_old_diagnostic_message, self.get_new_diagnostic_message) 00593 00594 00595 00596 ########### Vector3 ############### 00597 00598 00599 def get_old_vector3(self): 00600 vector3_classes = self.load_saved_classes('Vector3.saved') 00601 00602 vector3 = vector3_classes['robot_msgs/Vector3'] 00603 00604 return vector3(1.23, 4.56, 7.89) 00605 00606 def get_new_vector3(self): 00607 from geometry_msgs.msg import Vector3 00608 00609 return Vector3(1.23, 4.56, 7.89) 00610 00611 00612 def test_vector3(self): 00613 self.do_test('vector3', self.get_old_vector3, self.get_new_vector3) 00614 00615 00616 ########### Vector3Stamped ############### 00617 00618 00619 def get_old_vector3_stamped(self): 00620 vector3_classes = self.load_saved_classes('Vector3.saved') 00621 vector3_stamped_classes = self.load_saved_classes('Vector3Stamped.saved') 00622 00623 vector3 = vector3_classes['robot_msgs/Vector3'] 00624 vector3_stamped = vector3_stamped_classes['robot_msgs/Vector3Stamped'] 00625 00626 return vector3_stamped(None, vector3(1.23, 4.56, 7.89)) 00627 00628 def get_new_vector3_stamped(self): 00629 from geometry_msgs.msg import Vector3 00630 from geometry_msgs.msg import Vector3Stamped 00631 00632 return Vector3Stamped(None, Vector3(1.23, 4.56, 7.89)) 00633 00634 00635 def test_vector3_stamped(self): 00636 self.do_test('vector3_stamped', self.get_old_vector3_stamped, self.get_new_vector3_stamped) 00637 00638 00639 ########### Quaternion ############### 00640 00641 00642 def get_old_quaternion(self): 00643 quaternion_classes = self.load_saved_classes('Quaternion.saved') 00644 00645 quaternion = quaternion_classes['robot_msgs/Quaternion'] 00646 00647 return quaternion(1.23, 4.56, 7.89, 1.23) 00648 00649 def get_new_quaternion(self): 00650 from geometry_msgs.msg import Quaternion 00651 00652 return Quaternion(1.23, 4.56, 7.89, 1.23) 00653 00654 00655 def test_quaternion(self): 00656 self.do_test('quaternion', self.get_old_quaternion, self.get_new_quaternion) 00657 00658 00659 ########### QuaternionStamped ############### 00660 00661 00662 def get_old_quaternion_stamped(self): 00663 quaternion_classes = self.load_saved_classes('QuaternionStamped.saved') 00664 00665 quaternion_stamped = quaternion_classes['robot_msgs/QuaternionStamped'] 00666 quaternion = quaternion_classes['robot_msgs/Quaternion'] 00667 00668 return quaternion_stamped(None, quaternion(1.23, 4.56, 7.89, 1.23)) 00669 00670 def get_new_quaternion_stamped(self): 00671 from geometry_msgs.msg import QuaternionStamped 00672 from geometry_msgs.msg import Quaternion 00673 00674 return QuaternionStamped(None, Quaternion(1.23, 4.56, 7.89, 1.23)) 00675 00676 00677 def test_quaternion_stamped(self): 00678 self.do_test('quaternion_stamped', self.get_old_quaternion_stamped, self.get_new_quaternion_stamped) 00679 00680 00681 ########### Point ############### 00682 00683 00684 def get_old_point(self): 00685 point_classes = self.load_saved_classes('Point.saved') 00686 00687 point = point_classes['robot_msgs/Point'] 00688 00689 return point(1.23, 4.56, 7.89) 00690 00691 def get_new_point(self): 00692 from geometry_msgs.msg import Point 00693 00694 return Point(1.23, 4.56, 7.89) 00695 00696 00697 def test_point(self): 00698 self.do_test('point', self.get_old_point, self.get_new_point) 00699 00700 00701 ########### PointStamped ############### 00702 00703 00704 def get_old_point_stamped(self): 00705 point_classes = self.load_saved_classes('PointStamped.saved') 00706 00707 point_stamped = point_classes['robot_msgs/PointStamped'] 00708 point = point_classes['robot_msgs/Point'] 00709 00710 return point_stamped(None, point(1.23, 4.56, 7.89)) 00711 00712 def get_new_point_stamped(self): 00713 from geometry_msgs.msg import PointStamped 00714 from geometry_msgs.msg import Point 00715 00716 return PointStamped(None, Point(1.23, 4.56, 7.89)) 00717 00718 00719 def test_point_stamped(self): 00720 self.do_test('point_stamped', self.get_old_point_stamped, self.get_new_point_stamped) 00721 00722 00723 ########### Point32 ############### 00724 00725 00726 def get_old_point32(self): 00727 point32_classes = self.load_saved_classes('Point32.saved') 00728 00729 point32 = point32_classes['robot_msgs/Point32'] 00730 00731 return point32(1.23, 4.56, 7.89) 00732 00733 def get_new_point32(self): 00734 from geometry_msgs.msg import Point32 00735 00736 return Point32(1.23, 4.56, 7.89) 00737 00738 00739 def test_point32(self): 00740 self.do_test('point32', self.get_old_point32, self.get_new_point32) 00741 00742 00743 ########### Transform ############### 00744 00745 00746 def get_old_transform(self): 00747 transform_classes = self.load_saved_classes('Transform.saved') 00748 00749 transform = transform_classes['robot_msgs/Transform'] 00750 vector3 = transform_classes['robot_msgs/Vector3'] 00751 quaternion = transform_classes['robot_msgs/Quaternion'] 00752 00753 return transform(vector3(1.23, 4.56, 7.89), quaternion(0,0,0,1)) 00754 00755 def get_new_transform(self): 00756 from geometry_msgs.msg import Transform 00757 from geometry_msgs.msg import Vector3 00758 from geometry_msgs.msg import Quaternion 00759 00760 return Transform(Vector3(1.23, 4.56, 7.89), Quaternion(0,0,0,1)) 00761 00762 00763 def test_transform(self): 00764 self.do_test('transform', self.get_old_transform, self.get_new_transform) 00765 00766 00767 ########### TransformStamped ############### 00768 00769 00770 def get_old_transform_stamped(self): 00771 transform_classes = self.load_saved_classes('TransformStamped.saved') 00772 00773 transform_stamped = transform_classes['robot_msgs/TransformStamped'] 00774 transform = transform_classes['robot_msgs/Transform'] 00775 vector3 = transform_classes['robot_msgs/Vector3'] 00776 quaternion = transform_classes['robot_msgs/Quaternion'] 00777 00778 ts = transform_stamped(None, "parent_frame", transform(vector3(1.23, 4.56, 7.89), quaternion(0,0,0,1))) 00779 ts.header.frame_id = "child_frame" 00780 return ts 00781 00782 def get_old_transform_stamped_parent_id(self): 00783 transform_classes = self.load_saved_classes('TransformStamped_parent_id.saved') 00784 00785 transform_stamped = transform_classes['geometry_msgs/TransformStamped'] 00786 transform = transform_classes['geometry_msgs/Transform'] 00787 vector3 = transform_classes['geometry_msgs/Vector3'] 00788 quaternion = transform_classes['geometry_msgs/Quaternion'] 00789 header = transform_classes['std_msgs/Header'] 00790 00791 ts = transform_stamped(None, "parent_frame", transform(vector3(1.23, 4.56, 7.89), quaternion(0,0,0,1))) 00792 ts.header.frame_id = "child_frame" 00793 return ts 00794 00795 def get_new_transform_stamped(self): 00796 from geometry_msgs.msg import TransformStamped 00797 from geometry_msgs.msg import Transform 00798 from geometry_msgs.msg import Vector3 00799 from geometry_msgs.msg import Quaternion 00800 ts = TransformStamped(None, "child_frame", Transform(Vector3(1.23, 4.56, 7.89), Quaternion(0,0,0,1))) 00801 ts.header.frame_id = "parent_frame" 00802 return ts 00803 00804 def test_transform_stamped(self): 00805 self.do_test('transform_stamped', self.get_old_transform_stamped, self.get_new_transform_stamped) 00806 00807 def test_transform_stamped_parent_id(self): 00808 self.do_test('transform_stamped_parent_id', self.get_old_transform_stamped_parent_id, self.get_new_transform_stamped) 00809 00810 00811 ########### Pose ############### 00812 00813 00814 def get_old_pose(self): 00815 pose_classes = self.load_saved_classes('Pose.saved') 00816 00817 pose = pose_classes['robot_msgs/Pose'] 00818 point = pose_classes['robot_msgs/Point'] 00819 quaternion = pose_classes['robot_msgs/Quaternion'] 00820 00821 return pose(point(1.23, 4.56, 7.89), quaternion(0,0,0,1)) 00822 00823 def get_new_pose(self): 00824 from geometry_msgs.msg import Pose 00825 from geometry_msgs.msg import Point 00826 from geometry_msgs.msg import Quaternion 00827 00828 return Pose(Point(1.23, 4.56, 7.89), Quaternion(0,0,0,1)) 00829 00830 00831 def test_pose(self): 00832 self.do_test('pose', self.get_old_pose, self.get_new_pose) 00833 00834 00835 00836 ########### PoseStamped ############### 00837 00838 00839 def get_old_pose_stamped(self): 00840 pose_classes = self.load_saved_classes('PoseStamped.saved') 00841 00842 pose_stamped = pose_classes['robot_msgs/PoseStamped'] 00843 pose = pose_classes['robot_msgs/Pose'] 00844 point = pose_classes['robot_msgs/Point'] 00845 quaternion = pose_classes['robot_msgs/Quaternion'] 00846 00847 return pose_stamped(None, pose(point(1.23, 4.56, 7.89), quaternion(0,0,0,1))) 00848 00849 def get_new_pose_stamped(self): 00850 from geometry_msgs.msg import PoseStamped 00851 from geometry_msgs.msg import Pose 00852 from geometry_msgs.msg import Point 00853 from geometry_msgs.msg import Quaternion 00854 00855 return PoseStamped(None, Pose(Point(1.23, 4.56, 7.89), Quaternion(0,0,0,1))) 00856 00857 00858 def test_pose_stamped(self): 00859 self.do_test('pose_stamped', self.get_old_pose_stamped, self.get_new_pose_stamped) 00860 00861 00862 00863 ########### VOPose ############### 00864 00865 00866 # def get_old_vo_pose(self): 00867 # vo_pose_classes = self.load_saved_classes('VOPose.saved') 00868 # 00869 # vo_pose = vo_pose_classes['robot_msgs/VOPose'] 00870 # pose = vo_pose_classes['robot_msgs/Pose'] 00871 # point = vo_pose_classes['robot_msgs/Point'] 00872 # quaternion = vo_pose_classes['robot_msgs/Quaternion'] 00873 # 00874 # return vo_pose(None, pose(point(1.23, 4.56, 7.89), quaternion(0,0,0,1)), 123) 00875 # 00876 # def get_new_vo_pose(self): 00877 # from deprecated_msgs.msg import VOPose 00878 # from geometry_msgs.msg import Pose 00879 # from geometry_msgs.msg import Point 00880 # from geometry_msgs.msg import Quaternion 00881 # 00882 # return VOPose(None, Pose(Point(1.23, 4.56, 7.89), Quaternion(0,0,0,1)), 123) 00883 # 00884 # 00885 # def test_vo_pose(self): 00886 # self.do_test('vo_pose', self.get_old_vo_pose, self.get_new_vo_pose) 00887 00888 00889 00890 ########### PoseWithCovariance ############### 00891 00892 00893 def get_old_pose_with_covariance(self): 00894 pose_with_covariance_classes = self.load_saved_classes('PoseWithCovariance.saved') 00895 00896 pose_with_covariance = pose_with_covariance_classes['robot_msgs/PoseWithCovariance'] 00897 pose = pose_with_covariance_classes['robot_msgs/Pose'] 00898 point = pose_with_covariance_classes['robot_msgs/Point'] 00899 quaternion = pose_with_covariance_classes['robot_msgs/Quaternion'] 00900 00901 return pose_with_covariance(None, pose(point(1.23, 4.56, 7.89), quaternion(0,0,0,1)), identity6x6) 00902 00903 def get_new_pose_with_covariance(self): 00904 from geometry_msgs.msg import PoseWithCovarianceStamped 00905 from geometry_msgs.msg import PoseWithCovariance 00906 from geometry_msgs.msg import Pose 00907 from geometry_msgs.msg import Point 00908 from geometry_msgs.msg import Quaternion 00909 00910 return PoseWithCovarianceStamped(None, PoseWithCovariance(Pose(Point(1.23, 4.56, 7.89), Quaternion(0,0,0,1)), identity6x6)) 00911 00912 00913 def test_pose_with_covariance(self): 00914 self.do_test('pose_with_covariance', self.get_old_pose_with_covariance, self.get_new_pose_with_covariance) 00915 00916 00917 00918 ########### PoseDot ############### 00919 00920 00921 def get_old_pose_dot(self): 00922 pose_dot_classes = self.load_saved_classes('PoseDot.saved') 00923 00924 pose_dot = pose_dot_classes['robot_msgs/PoseDot'] 00925 velocity = pose_dot_classes['robot_msgs/Velocity'] 00926 angular_velocity = pose_dot_classes['robot_msgs/AngularVelocity'] 00927 00928 return pose_dot(velocity(1.23, 4.56, 7.89), angular_velocity(9.87, 6.54, 3.21)) 00929 00930 def get_new_pose_dot(self): 00931 from geometry_msgs.msg import Twist 00932 from geometry_msgs.msg import Vector3 00933 00934 return Twist(Vector3(1.23, 4.56, 7.89), Vector3(9.87, 6.54, 3.21)) 00935 00936 def test_pose_dot(self): 00937 self.do_test('pose_dot', self.get_old_pose_dot, self.get_new_pose_dot) 00938 00939 00940 00941 00942 ########### Particle Cloud ############### 00943 00944 00945 def get_old_particle_cloud(self): 00946 particle_cloud_classes = self.load_saved_classes('ParticleCloud.saved') 00947 00948 particle_cloud = particle_cloud_classes['robot_msgs/ParticleCloud'] 00949 pose = particle_cloud_classes['robot_msgs/Pose'] 00950 point = particle_cloud_classes['robot_msgs/Point'] 00951 quaternion = particle_cloud_classes['robot_msgs/Quaternion'] 00952 00953 return particle_cloud([pose(point(1.23, 4.56, 7.89), quaternion(1,0,0,1)), 00954 pose(point(1.25, 4.58, 7.91), quaternion(0,1,0,1)), 00955 pose(point(1.27, 4.60, 7.93), quaternion(0,0,1,1))]) 00956 00957 def get_new_particle_cloud(self): 00958 from geometry_msgs.msg import PoseArray 00959 from geometry_msgs.msg import Pose 00960 from geometry_msgs.msg import Point 00961 from geometry_msgs.msg import Quaternion 00962 00963 return PoseArray(None, [Pose(Point(1.23, 4.56, 7.89), Quaternion(1,0,0,1)), 00964 Pose(Point(1.25, 4.58, 7.91), Quaternion(0,1,0,1)), 00965 Pose(Point(1.27, 4.60, 7.93), Quaternion(0,0,1,1))]) 00966 00967 00968 def test_particle_cloud(self): 00969 self.do_test('particle_cloud', self.get_old_particle_cloud, self.get_new_particle_cloud) 00970 00971 00972 00973 ########### Path ############### 00974 00975 00976 def get_old_path(self): 00977 path_classes = self.load_saved_classes('Path.saved') 00978 00979 00980 00981 path = path_classes['robot_msgs/Path'] 00982 header = path_classes['std_msgs/Header'] 00983 pose_stamped = path_classes['robot_msgs/PoseStamped'] 00984 pose = path_classes['robot_msgs/Pose'] 00985 point = path_classes['robot_msgs/Point'] 00986 quaternion = path_classes['robot_msgs/Quaternion'] 00987 00988 return path([pose_stamped(header(0,rospy.Time(0,0),'foo'), pose(point(1.23, 4.56, 7.89), quaternion(1,0,0,1))), 00989 pose_stamped(header(0,rospy.Time(0,1000),'foo'), pose(point(1.25, 4.58, 7.91), quaternion(0,1,0,1))), 00990 pose_stamped(header(0,rospy.Time(0,2000),'foo'), pose(point(1.27, 4.60, 7.93), quaternion(0,0,1,1)))]) 00991 00992 def get_new_path(self): 00993 from nav_msgs.msg import Path 00994 from std_msgs.msg import Header 00995 from geometry_msgs.msg import PoseStamped 00996 from geometry_msgs.msg import Pose 00997 from geometry_msgs.msg import Point 00998 from geometry_msgs.msg import Quaternion 00999 01000 return Path(None, [PoseStamped(Header(0,rospy.Time(0,0),'foo'), Pose(Point(1.23, 4.56, 7.89), Quaternion(1,0,0,1))), 01001 PoseStamped(Header(0,rospy.Time(0,1000),'foo'), Pose(Point(1.25, 4.58, 7.91), Quaternion(0,1,0,1))), 01002 PoseStamped(Header(0,rospy.Time(0,2000),'foo'), Pose(Point(1.27, 4.60, 7.93), Quaternion(0,0,1,1)))]) 01003 01004 01005 def test_path(self): 01006 self.do_test('path', self.get_old_path, self.get_new_path) 01007 01008 01009 01010 01011 ########### Velocity ############### 01012 01013 01014 def get_old_velocity(self): 01015 velocity_classes = self.load_saved_classes('Velocity.saved') 01016 01017 velocity = velocity_classes['robot_msgs/Velocity'] 01018 01019 return velocity(1.23, 4.56, 7.89) 01020 01021 def get_new_velocity(self): 01022 from geometry_msgs.msg import Vector3 01023 01024 return Vector3(1.23, 4.56, 7.89) 01025 01026 01027 def test_velocity(self): 01028 self.do_test('velocity', self.get_old_velocity, self.get_new_velocity) 01029 01030 01031 ########### Angular Velocity ############### 01032 01033 01034 def get_old_angular_velocity(self): 01035 angular_velocity_classes = self.load_saved_classes('AngularVelocity.saved') 01036 01037 angular_velocity = angular_velocity_classes['robot_msgs/AngularVelocity'] 01038 01039 return angular_velocity(1.23, 4.56, 7.89) 01040 01041 def get_new_angular_velocity(self): 01042 from geometry_msgs.msg import Vector3 01043 01044 return Vector3(1.23, 4.56, 7.89) 01045 01046 01047 def test_angular_velocity(self): 01048 self.do_test('angular_velocity', self.get_old_angular_velocity, self.get_new_angular_velocity) 01049 01050 01051 ########### Twist ############### 01052 01053 01054 def get_old_twist(self): 01055 twist_classes = self.load_saved_classes('Twist.saved') 01056 01057 twist = twist_classes['robot_msgs/Twist'] 01058 vector3 = twist_classes['robot_msgs/Vector3'] 01059 01060 return twist(None, vector3(1,2,3), vector3(4, 5, 6)) 01061 01062 def get_new_twist(self): 01063 from geometry_msgs.msg import TwistStamped 01064 from geometry_msgs.msg import Twist 01065 from geometry_msgs.msg import Vector3 01066 01067 return TwistStamped(None, Twist(Vector3(1,2,3), Vector3(4, 5, 6))) 01068 01069 01070 def test_twist(self): 01071 self.do_test('twist', self.get_old_twist, self.get_new_twist) 01072 01073 01074 01075 01076 ########### Wrench ############### 01077 01078 01079 def get_old_wrench(self): 01080 wrench_classes = self.load_saved_classes('Wrench.saved') 01081 01082 wrench = wrench_classes['robot_msgs/Wrench'] 01083 vector3 = wrench_classes['robot_msgs/Vector3'] 01084 01085 return wrench(None, vector3(1,2,3), vector3(4, 5, 6)) 01086 01087 def get_new_wrench(self): 01088 from geometry_msgs.msg import WrenchStamped 01089 from geometry_msgs.msg import Wrench 01090 from geometry_msgs.msg import Vector3 01091 01092 return WrenchStamped(None, Wrench(Vector3(1,2,3), Vector3(4, 5, 6))) 01093 01094 01095 def test_wrench(self): 01096 self.do_test('wrench', self.get_old_wrench, self.get_new_wrench) 01097 01098 01099 ########### Channelfloat32 ############### 01100 01101 01102 def get_old_channelfloat32(self): 01103 channelfloat32_classes = self.load_saved_classes('ChannelFloat32.saved') 01104 01105 channelfloat32 = channelfloat32_classes['robot_msgs/ChannelFloat32'] 01106 01107 return channelfloat32("myname", [1.23, 4.56, 7.89]) 01108 01109 def get_new_channelfloat32(self): 01110 from sensor_msgs.msg import ChannelFloat32 01111 01112 return ChannelFloat32("myname", [1.23, 4.56, 7.89]) 01113 01114 01115 def test_channelfloat32(self): 01116 self.do_test('channelfloat32', self.get_old_channelfloat32, self.get_new_channelfloat32) 01117 01118 01119 ########### PointCloud ############### 01120 01121 01122 def get_old_pointcloud(self): 01123 pointcloud_classes = self.load_saved_classes('PointCloud.saved') 01124 01125 pointcloud = pointcloud_classes['robot_msgs/PointCloud'] 01126 point32 = pointcloud_classes['robot_msgs/Point32'] 01127 channelfloat32 = pointcloud_classes['robot_msgs/ChannelFloat32'] 01128 01129 points = [point32(1,2,3), point32(4,5,6)] 01130 channels = [channelfloat32("myname1", [1.23, 4.56]), 01131 channelfloat32("myname2", [1.231, 4.561])] 01132 return pointcloud(None, points, channels) 01133 01134 def get_new_pointcloud(self): 01135 from sensor_msgs.msg import PointCloud 01136 from geometry_msgs.msg import Point32 01137 from sensor_msgs.msg import ChannelFloat32 01138 01139 Points = [Point32(1,2,3), Point32(4,5,6)] 01140 Channels = [ChannelFloat32("myname1", [1.23, 4.56]), 01141 ChannelFloat32("myname2", [1.231, 4.561])] 01142 01143 01144 return PointCloud(None, Points, Channels) 01145 01146 01147 def test_pointcloud(self): 01148 self.do_test('pointcloud', self.get_old_pointcloud, self.get_new_pointcloud) 01149 01150 01151 ########### Helper functions ########### 01152 01153 def setUp(self): 01154 self.pkg_dir = roslib.packages.get_pkg_dir("test_common_msgs") 01155 01156 01157 def load_saved_classes(self,saved_msg): 01158 f = open("%s/test/saved/%s"%(self.pkg_dir,saved_msg), 'r') 01159 01160 type_line = f.readline() 01161 pat = re.compile(r"\[(.*)]:") 01162 type_match = pat.match(type_line) 01163 01164 self.assertTrue(type_match is not None, "Full definition file malformed. First line should be: '[my_package/my_msg]:'") 01165 01166 saved_type = type_match.groups()[0] 01167 saved_full_text = f.read() 01168 01169 saved_classes = roslib.genpy.generate_dynamic(saved_type,saved_full_text) 01170 01171 self.assertTrue(saved_classes is not None, "Could not generate class from full definition file.") 01172 self.assertTrue(saved_classes.has_key(saved_type), "Could not generate class from full definition file.") 01173 01174 return saved_classes 01175 01176 def do_test(self, name, old_msg, new_msg): 01177 # Name the bags 01178 oldbag = "%s/test/%s_old.bag"%(self.pkg_dir,name) 01179 newbag = "%s/test/%s_new.bag"%(self.pkg_dir,name) 01180 01181 # Create an old message 01182 bag = rosbag.Bag(oldbag, 'w') 01183 bag.write("topic", old_msg(), roslib.rostime.Time()) 01184 bag.close() 01185 01186 # Check and migrate 01187 res = rosbag.migration.checkbag(migrator, oldbag) 01188 self.assertTrue(not False in [m[1] == [] for m in res], 'Bag not ready to be migrated') 01189 res = rosbag.migration.fixbag(migrator, oldbag, newbag) 01190 self.assertTrue(res, 'Bag not converted successfully') 01191 01192 # Pull the first message out of the bag 01193 topic, msg, t = rosbag.Bag(newbag).read_messages().next() 01194 01195 # Reserialize the new message so that floats get screwed up, etc. 01196 m = new_msg() 01197 buff = StringIO() 01198 m.serialize(buff) 01199 m.deserialize(buff.getvalue()) 01200 01201 # Strifying them helps make the comparison easier until I figure out why the equality operator is failing 01202 self.assertTrue(roslib.message.strify_message(msg) == roslib.message.strify_message(m)) 01203 # self.assertTrue(msgs[0][1] == m) 01204 01205 #Cleanup 01206 os.remove(oldbag) 01207 os.remove(newbag) 01208 01209 01210 01211 01212 01213 if __name__ == '__main__': 01214 rostest.unitrun('test_common_msgs', 'test_common_msgs_migration', TestCommonMsgsMigration, sys.argv)