Go to the documentation of this file.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
00035 roslib.load_manifest('dense_laser_assembler')
00036 
00037 import time
00038 import rospy
00039 import sys
00040 import threading
00041 from laser_scan.msg import *
00042 from roslib import rostime
00043 
00044 
00045 class LaserCacheElem() :
00046     pass
00047 
00048 
00049 class DenseLaserCache() :
00050     def __init__(self, req_callback, max_mech_len, max_laser_done_len, max_laser_wait_len) :
00051 
00052         
00053         self._req_callback = req_callback
00054 
00055         
00056         self._max_mech_len = max_mech_len
00057         self._max_laser_done_len = max_laser_done_len
00058         self._max_laser_wait_len = max_laser_wait_len
00059 
00060         
00061         self._mech_lock = threading.Lock()
00062         self._laser_done_lock = threading.Lock()
00063         self._laser_wait_lock = threading.Lock()
00064         self._interval_req_lock = threading.Lock()
00065 
00066         
00067         self._mech_q = [ ]        
00068         self._laser_done_q = []   
00069         self._laser_wait_q = []   
00070         self._interval_req_q = [] 
00071 
00072     def add_mech_state(self, msg) :
00073         self._mech_lock.acquire()
00074         self._mech_q.append(msg)
00075         while len(self._mech_q) > self._max_mech_len :
00076             self._mech_q.pop(0)
00077         self._mech_lock.release()
00078 
00079     def add_scan(self, msg) :
00080         self._laser_wait_lock.acquire()
00081         self._laser_wait_q.append(msg)
00082         while len(self._laser_wait_q) > self._max_laser_wait_len :
00083             self._laser_wait_q.pop(0)
00084         self._laser_wait_lock.release()
00085 
00086     
00087     
00088     
00089     
00090     def process_scans(self) :
00091         self._mech_lock.acquire()
00092 
00093         if len(self._mech_q) > 0 :
00094             oldest_mech_time = self._mech_q[0].header.stamp
00095             newest_mech_time = self._mech_q[-1].header.stamp
00096         else :
00097             self._mech_lock.release()
00098             return
00099 
00100         self._laser_wait_lock.acquire()
00101 
00102         scan_interval = [ (x.header.stamp,
00103 
00104                            x.header.stamp+rostime.Duration().from_seconds(len(x.ranges)*x.time_increment))
00105                            for x in self._laser_wait_q ]
00106 
00107         laser_pending_q = [x for i,x in enumerate(self._laser_wait_q)
00108                              if scan_interval[i][1] < newest_mech_time and
00109                                 scan_interval[i][0] > oldest_mech_time]
00110         
00111         self._laser_wait_q = [x for i,x in enumerate(self._laser_wait_q)
00112                                 if scan_interval[i][1] >= newest_mech_time]
00113 
00114         self._laser_wait_lock.release()
00115 
00116         
00117         processed = [self._process_pending(x,self._mech_q) for x in laser_pending_q]
00118 
00119         
00120         
00121 
00122         self._laser_done_lock.acquire()
00123         self._laser_done_q = self._laser_done_q + processed
00124         while len(self._laser_done_q) > self._max_laser_done_len :
00125             self._laser_done_q.pop(0)
00126         self._laser_done_lock.release()
00127         self._mech_lock.release()
00128     
00129     
00130     
00131     
00132     def _process_pending(self, scan_msg, mech_q):
00133         scan_end = scan_msg.header.stamp + rostime.Duration().from_seconds(len(scan_msg.ranges)*scan_msg.time_increment)
00134         mech_before = [x for x in mech_q if x.header.stamp < scan_msg.header.stamp][-1]
00135         mech_after  = [x for x in mech_q if x.header.stamp > scan_end][0]
00136 
00137         
00138         ind = [x.name for x in mech_before.joint_states].index('laser_tilt_mount_joint')
00139         pos_before = mech_before.joint_states[ind].position
00140         time_before= mech_before.header.stamp
00141 
00142         
00143         ind = [x.name for x in mech_after.joint_states].index('laser_tilt_mount_joint')
00144         pos_after = mech_after.joint_states[ind].position
00145         time_after= mech_after.header.stamp
00146 
00147         elapsed = (time_after - time_before).to_seconds()
00148 
00149         
00150         
00151 
00152         
00153         key_rays = [0, len(scan_msg.ranges)-1]
00154         time_during = [ scan_msg.header.stamp
00155                         + rostime.Duration().from_seconds(scan_msg.time_increment*x)
00156                           for x in key_rays]
00157         time_normalized = [ (x - time_before).to_seconds()/elapsed for x in time_during]
00158         if any( [x > 1 for x in time_normalized]) or any( [x < 0 for x in time_normalized] ) :
00159             print 'Error computing normalized time'
00160         pos_during = [ pos_before * (1-x) + pos_after * x for x in time_normalized ]
00161 
00162         elem = LaserCacheElem()
00163         elem.pos  = pos_during
00164         elem.scan = scan_msg
00165         return elem
00166 
00167     
00168     def get_dense_cloud(self, start, end) :
00169         self._laser_done_lock.acquire()
00170         trimmed_done = [x for x in self._laser_done_q
00171                           if x.scan.header.stamp <= end and
00172                              x.scan.header.stamp >= start]
00173         self._laser_done_lock.release()
00174         return trimmed_done
00175 
00176     
00177     def get_latest_done_scan_time(self) :
00178         self._laser_done_lock.acquire()
00179         if len(self._laser_done_q) > 0 :
00180             latest_time = self._laser_done_q[-1].scan.header.stamp
00181         else :
00182             latest_time = rostime.Time().from_seconds(0.0)
00183         self._laser_done_lock.release()
00184         return latest_time
00185 
00186     
00187     
00188     def add_interval_req(self, start, end) :
00189         self._interval_req_lock.acquire()
00190         self._interval_req_q.append([start, end])
00191         self._interval_req_lock.release()
00192         self.process_interval_reqs()
00193 
00194     
00195     
00196     
00197     def process_interval_reqs(self) :
00198 
00199         latest_time = self.get_latest_done_scan_time()
00200 
00201         
00202         self._interval_req_lock.acquire()
00203         pending_reqs = [x for x in self._interval_req_q if x[1] <  latest_time]
00204         idle_reqs =    [x for x in self._interval_req_q if x[1] >= latest_time]
00205         self._interval_req_q = idle_reqs
00206         self._interval_req_lock.release()
00207 
00208         
00209         clouds = [self.get_dense_cloud(x[0], x[1]) for x in pending_reqs]
00210 
00211         for x in clouds :
00212             self._req_callback(x)