00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 import roslib; roslib.load_manifest('camera_pose_calibration')
00035 import rospy
00036 import yaml
00037 import sys
00038 import actionlib
00039 import time
00040 import threading
00041 import message_filters
00042
00043 from camera_pose_calibration.robot_measurement_cache import RobotMeasurementCache
00044
00045 from calibration_msgs.msg import Interval, CalibrationPattern
00046 from camera_pose_calibration.msg import RobotMeasurement, CameraMeasurement
00047 from sensor_msgs.msg import CameraInfo, Image
00048
00049
00050 class CameraCaptureExecutive:
00051 def __init__(self, cam_ids):
00052 self.cam_ids = cam_ids
00053 self.cache = RobotMeasurementCache()
00054 self.lock = threading.Lock()
00055
00056
00057 self.active = False
00058
00059
00060 cam_info_topic = rospy.get_param('~cam_info_topic', 'camera_info')
00061 self.cam_managers = [ (cam_id, CamManager( cam_id, cam_info_topic,
00062 self.add_cam_measurement) ) for cam_id in cam_ids ]
00063
00064
00065 for cam_manager in zip(*self.cam_managers)[1]:
00066 cam_manager.enable(verbose=True)
00067
00068
00069 self.measurement_pub = rospy.Publisher("robot_measurement", RobotMeasurement)
00070 self.request_interval_sub = rospy.Subscriber("request_interval", Interval, self.request_callback)
00071
00072
00073 chain_ids = []
00074 laser_ids = []
00075 self.cache.reconfigure(cam_ids, chain_ids, laser_ids)
00076
00077 def request_callback(self, msg):
00078
00079 print "Got a request callback"
00080
00081
00082
00083
00084
00085 with self.lock:
00086
00087 m_robot = self.cache.request_robot_measurement(msg.start, msg.end, min_duration=rospy.Duration(0.01))
00088
00089
00090 if m_robot:
00091
00092 for cam in m_robot.M_cam:
00093 cam.camera_id = cam.cam_info.header.frame_id
00094 m_robot.header.stamp = cam.cam_info.header.stamp
00095 self.measurement_pub.publish(m_robot)
00096 else:
00097 print "Couldn't get measurement in interval"
00098
00099
00100 def add_cam_measurement(self, cam_id, msg):
00101
00102 if len(msg.features.image_points) > 0:
00103 with self.lock:
00104 self.cache.add_cam_measurement(cam_id, msg)
00105
00106
00107 class CamManager:
00108 def __init__(self, cam_id, cam_info_topic, callback):
00109 self._cam_id = cam_id
00110 self._callback = callback
00111 self._mode = "off"
00112
00113 self._lock = threading.Lock()
00114
00115
00116 self._features_sub = message_filters.Subscriber(cam_id + "/features", CalibrationPattern)
00117 self._cam_info_sub = message_filters.Subscriber(cam_id + "/" + cam_info_topic, CameraInfo)
00118
00119 self._verbose_sync = message_filters.TimeSynchronizer([self._cam_info_sub, self._features_sub], 10)
00120
00121 self._verbose_sync.registerCallback(self.verbose_callback)
00122
00123 def verbose_callback(self, cam_info, features):
00124 with self._lock:
00125 if self._mode is "verbose":
00126
00127 msg = CameraMeasurement()
00128 msg.header.stamp = cam_info.header.stamp
00129 msg.camera_id = self._cam_id
00130 msg.cam_info = cam_info
00131 msg.features = features
00132 self._callback(self._cam_id, msg)
00133
00134 def enable(self, verbose=False):
00135 with self._lock:
00136 self._mode = "verbose"
00137
00138 def disable(self):
00139 with self._lock:
00140 self._mode = "off"
00141
00142
00143 if __name__ == '__main__':
00144 rospy.init_node('capture_exec')
00145 args = rospy.myargv(sys.argv)
00146
00147
00148 if len(args) < 2:
00149 rospy.logfatal("multicam_capture_exec.py needs camera's as arguments")
00150 raise
00151 camera_list = args[1:]
00152 executive = CameraCaptureExecutive(camera_list)
00153 rospy.spin()