00001
00002
00003
00004 from __future__ import with_statement
00005
00006 PKG = 'articulation_closedchain'
00007 NAME = 'track_assembler'
00008 import roslib; roslib.load_manifest(PKG)
00009
00010 import rospy
00011 import cv
00012 import math
00013 import threading
00014 import numpy
00015 import tf
00016 import articulation_models
00017 from articulation_models.transform_datatypes import mat44_to_pose,pose_to_mat44
00018
00019 from geometry_msgs.msg import PoseStamped,Pose,Point,Quaternion
00020 from articulation_msgs.msg import TrackMsg,ModelMsg
00021
00022 class TrajAssemblerNode:
00023 def __init__(self):
00024 self.markers = rospy.get_param('~markers', 4)
00025
00026
00027 self.marker_sub = []
00028 self.marker_sub.append(rospy.Subscriber("/marker/1", PoseStamped, self.callback1))
00029 self.marker_sub.append(rospy.Subscriber("/marker/2", PoseStamped, self.callback2))
00030 self.marker_sub.append(rospy.Subscriber("/marker/3", PoseStamped, self.callback3))
00031 self.marker_sub.append(rospy.Subscriber("/marker/4", PoseStamped, self.callback4))
00032 self.track_pub = rospy.Publisher('track', TrackMsg)
00033 self.mutex = threading.RLock()
00034 self.pose = {}
00035
00036 self.track = TrackMsg()
00037
00038 def callback1(self, pose):
00039 self.add_pose(1,pose)
00040 if(len(self.pose[1])%3 ==0):
00041 print "sending tracks."
00042 self.send_track()
00043
00044 def callback2(self, pose):
00045 self.add_pose(2,pose)
00046
00047 def callback3(self, pose):
00048 self.add_pose(3,pose)
00049
00050 def callback4(self, pose):
00051 self.add_pose(4,pose)
00052
00053 def add_pose(self,marker,pose):
00054 with self.mutex:
00055 if not marker in self.pose:
00056 self.pose[marker] = {}
00057 self.pose[marker][pose.header.stamp.to_sec()] = pose.pose
00058 print "added marker %d timestamp %f"%(marker,pose.header.stamp.to_sec())
00059
00060 def send_track(self):
00061 with self.mutex:
00062
00063
00064 for (m1,m2) in [(2,1),(3,2),(4,3),(1,4)]:
00065 if m2==m1:
00066 continue
00067 track = TrackMsg()
00068 track.header.stamp = rospy.get_rostime()
00069 track.header.frame_id = "/camera"
00070
00071 track.id = m1*len(self.pose.keys()) + m2
00072 keys1 = self.pose[m1].keys()
00073 keys2 = self.pose[m2].keys()
00074 keys = filter(lambda x:x in keys1,keys2)
00075 keys.sort()
00076 mat1_last = pose_to_mat44(self.pose[m1][keys[-1]])
00077
00078 for time in keys:
00079 pose1 = self.pose[m1][time]
00080 pose2 = self.pose[m2][time]
00081 mat1=pose_to_mat44(pose1)
00082 mat2=pose_to_mat44(pose2)
00083 diff = numpy.mat(mat1).I * mat2
00084 diff_pose = mat44_to_pose(diff)
00085 diff[2,3] = 0.00
00086 pose_rel_to_last = mat44_to_pose(mat1_last * diff)
00087 track.pose.append(pose_rel_to_last)
00088 self.track_pub.publish(track)
00089
00090 def main(argv=None):
00091 rospy.init_node(NAME, anonymous=False)
00092 assembler = TrajAssemblerNode()
00093 rospy.spin()
00094
00095 if __name__ == '__main__':
00096 main()
00097