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 logging
00014 import getopt
00015 import colorsys
00016 import numpy
00017 import copy
00018 import rosbag
00019
00020 def all_detected(pose_array):
00021 for p in pose_array.poses:
00022 r = [p.orientation.x,p.orientation.y,p.orientation.z,p.orientation.w]
00023 if( numpy.dot(r,r) == 0 ):
00024 return False
00025 return True
00026
00027 def main():
00028 rospy.init_node('articulation_eval')
00029
00030 info_pub = rospy.Publisher('/camera/camera_info',CameraInfo)
00031 image_pub = rospy.Publisher('/camera/image_raw/compressed',CompressedImage)
00032 posearray_pub = rospy.Publisher('/camera/pose_array',PoseArray)
00033 model_pub = rospy.Publisher('/model', ModelMsg)
00034 track_pub = rospy.Publisher('/track', TrackMsg)
00035
00036 fit_models = rospy.ServiceProxy('fit_models', ArticulatedObjectSrv)
00037 get_spanning_tree = rospy.ServiceProxy('get_spanning_tree', ArticulatedObjectSrv)
00038 get_fast_graph = rospy.ServiceProxy('get_fast_graph', ArticulatedObjectSrv)
00039 get_graph = rospy.ServiceProxy('get_graph', ArticulatedObjectSrv)
00040 get_graph_all = rospy.ServiceProxy('get_graph_all', ArticulatedObjectSrv)
00041 visualize_graph = rospy.ServiceProxy('visualize_graph', ArticulatedObjectSrv)
00042
00043 downsample = rospy.get_param("~downsample",100)
00044 first_n = rospy.get_param("~first_n",0)
00045 start_n = rospy.get_param("~start_n",0)
00046 sigma_position = rospy.get_param("~sigma_position",0.005)
00047 sigma_orientation = rospy.get_param("~sigma_orientation",0.4)
00048 sigmax_position = rospy.get_param("~sigmax_position",0.005)
00049 sigmax_orientation = rospy.get_param("~sigmax_orientation",0.4)
00050 reduce_dofs = rospy.get_param("~reduce_dofs",1)
00051 mode = rospy.get_param("~mode","spanningtree")
00052
00053
00054
00055
00056
00057
00058 inbag_filename = rospy.get_param('~bagfile','/home/sturm/sturm-data/sturm10tro/cabinet-pose.bag')
00059
00060
00061 bag = {}
00062 for topic, msg, t in rosbag.Bag(inbag_filename).read_messages():
00063 timestamp = t
00064 if not timestamp in bag:
00065 bag[timestamp] = {}
00066 bag[timestamp][topic] = msg
00067 print "read bagfile %s with %d different header timestamps"%( inbag_filename, len(bag) )
00068 topics = max([len(msgs.keys()) for (timestamp,msgs) in bag.iteritems()])
00069 for (timestamp) in bag.keys():
00070 if len( bag[timestamp] ) != topics or not all_detected(bag[timestamp]['/camera/pose_array']):
00071 del bag[timestamp]
00072
00073
00074
00075
00076
00077 timestamps = bag.keys()
00078 timestamps.sort()
00079 if(first_n>0):
00080 timestamps = timestamps[0:first_n]
00081
00082
00083 sequence = [ bag[timestamp]['/camera/pose_array'] for timestamp in timestamps ]
00084 parts = len( sequence[0].poses )
00085 print "read %d observations of %d object parts"%(len(bag),parts)
00086 downsampled = [ i for i in range(len(timestamps)) if (i % (max(1,(len(sequence)-start_n) / downsample)) == 0 ) and i>=start_n]
00087 downsampled = downsampled[len(downsampled) - downsample:]
00088 sequence_downsampled = [ sequence[i] for i in downsampled ]
00089 print "downsampled to %d pose observations"%len(sequence_downsampled)
00090
00091
00092
00093
00094
00095 request = ArticulatedObjectSrvRequest()
00096 request.object.header = sequence_downsampled[-1].header
00097 request.object.parts = [
00098 TrackMsg(
00099 id=i,
00100
00101 header=request.object.header,
00102 pose=[p.poses[i] for p in sequence_downsampled]
00103 )
00104 for i in range(parts)
00105 ]
00106 set_param(request.object, "sigma_position", sigma_position, ParamMsg.PRIOR)
00107 set_param(request.object, "sigma_orientation", sigma_orientation, ParamMsg.PRIOR)
00108 set_param(request.object, "sigmax_position", sigmax_position, ParamMsg.PRIOR)
00109 set_param(request.object, "sigmax_orientation", sigmax_orientation, ParamMsg.PRIOR)
00110 set_param(request.object, "reduce_dofs", reduce_dofs, ParamMsg.PRIOR)
00111
00112
00113
00114
00115
00116 print "fitting models"
00117 response = fit_models(request)
00118 print '\n'.join(
00119 ['(%s:%d,%d) bic=%f pos_err=%f rot_err=%f gamma=%f'%(
00120 model.name[0:2],
00121 model.id/parts,
00122 model.id%parts,
00123 get_param(model,'bic'),
00124 get_param(model,'avg_error_position'),
00125 get_param(model,'avg_error_orientation'),
00126 get_param(model,'outlier_ratio')
00127 ) for model in response.object.models])
00128
00129 if mode=="fastgraph":
00130 print "running fastgraph"
00131 response = get_fast_graph(request)
00132 elif mode=="graph":
00133 print "running graph"
00134 response = get_graph(request)
00135 elif mode=="spanningtree":
00136 print "running spanningtree"
00137 response = get_spanning_tree(request)
00138 elif mode=="all":
00139 print "running all structure selection methods"
00140 response = get_graph_all(request)
00141
00142 request.object = copy.deepcopy(response.object)
00143 response = visualize_graph(request)
00144
00145 rospy.loginfo('received articulation model: '+(' '.join(
00146 ['(%s:%d,%d)'%(model.name[0:2],model.id/parts,model.id%parts) for model in response.object.models])))
00147
00148 print '\n'.join(
00149 ['(%s:%d,%d) bic=%f pos_err=%f rot_err=%f'%(
00150 model.name[0:2],
00151 model.id/parts,
00152 model.id%parts,
00153 get_param(model,'bic'),
00154 get_param(model,'avg_error_position'),
00155 get_param(model,'avg_error_orientation')
00156 ) for model in response.object.models])
00157 print "dofs=%d, nominal dofs=%d, bic=%f pos_err=%f rot_err=%f"%(
00158 get_param(response.object,'dof'),
00159 get_param(response.object,'dof.nominal'),
00160 get_param(response.object,'bic'),
00161 get_param(response.object,'avg_error_position'),
00162 get_param(response.object,'avg_error_orientation')
00163 )
00164
00165
00166
00167
00168
00169 print response.object.params
00170
00171
00172
00173 last_timestamp = timestamps[ downsampled[-1] ]
00174 info_pub.publish( bag[last_timestamp]['/camera/camera_info'] )
00175 image_pub.publish( bag[last_timestamp]['/camera/image_raw/compressed'] )
00176 posearray_pub.publish( bag[last_timestamp]['/camera/pose_array'] )
00177
00178
00179
00180
00181
00182
00183 rospy.sleep(5)
00184
00185 if __name__ == '__main__':
00186 main()
00187