Go to the documentation of this file.00001
00002
00003 import roslib; roslib.load_manifest('articulation_structure')
00004 import rospy
00005 import sys
00006 from visualization_msgs.msg import Marker, MarkerArray
00007 from geometry_msgs.msg import Vector3, Point, Pose, PoseArray
00008 from std_msgs.msg import ColorRGBA
00009 from sensor_msgs.msg import ChannelFloat32,CameraInfo,CompressedImage
00010 from articulation_msgs.msg import *
00011 from articulation_msgs.srv import *
00012 from articulation_models.track_utils import *
00013 import process_bags
00014
00015 def main():
00016 rospy.init_node('process_structure')
00017 if len(rospy.myargv()) != 3:
00018 print "Usage: process_structure <in.bag> <out.bag>"
00019 return
00020
00021 infile = rospy.myargv()[1]
00022 outfile = rospy.myargv()[2]
00023
00024 in_topics = ['/camera/camera_info','/camera/image_raw/compressed',
00025 '/camera/pose_array','/camera/visualization_marker_array']
00026 in_types = [CameraInfo,CompressedImage,PoseArray,MarkerArray]
00027
00028 out_topics = ['/track','/model','/structure_array','/object']
00029 out_types = [TrackMsg,ModelMsg,MarkerArray,ArticulatedObjectMsg]
00030
00031 timeout = 5
00032
00033 process_bags.process_bags(infile,in_topics,in_types,
00034 outfile,out_topics,out_types,
00035 timeout)
00036
00037
00038 if __name__ == '__main__':
00039 main()
00040