plane_set_estimator.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2009, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of the Willow Garage nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 
00034 # Author: Bhaskara Marthi
00035 #
00036 # Maintain set of planes
00037 
00038 import roslib; roslib.load_manifest('semanticmodel')
00039 import rospy
00040 import semanticmodel.plane_data_association as pd
00041 import threading
00042 from semanticmodel import msg
00043 from semanticmodel import srv
00044 import visualization_msgs.msg as vm
00045 import time
00046 import math
00047 import logging
00048 import sys
00049 #import mongo_ros as mr
00050 
00051 
00052 LOG = logging.getLogger('world_model.planes')
00053 
00054 
00055 
00056 class PlaneSetEstimator:
00057     "Holds the ros independent logic for the plane set estimator"
00058     
00059     def __init__(self, max_disp):
00060         "Initialize estimator"
00061         self.max_disp = max_disp
00062         self.planes = {}             
00063         LOG.info('Initialized estimator')
00064         
00065 
00066     def process_plane(self, bp):
00067         "Combine with an existing plane or add a new one"
00068         int_planes = [id for id, existing_plane in self.planes.items()
00069                       if pd.intersect(bp, existing_plane, self.max_disp)]
00070         LOG.debug("Intersecting planes are {0}".format(int_planes))
00071         if int_planes:
00072             self.planes = pd.merge_planes(self.planes, bp, self.max_disp)
00073         else:
00074             LOG.debug("Adding new plane {0}".format(len(self.planes)))
00075             self.planes[len(self.planes)] = bp
00076         LOG.debug("Done processing plane")
00077         
00078 
00079     def get_containing_plane(self, bp):
00080         int_planes = [pl for id, pl in self.planes.items()
00081                       if pd.intersect(bp, pl, self.max_disp)]
00082         LOG.debug("Intersecting planes are {0}".format(int_planes))
00083         combined_plane = bp
00084         for p in int_planes:
00085             combined_plane = pd.combine(combined_plane, p)
00086             LOG.debug("Combined plane is now {0}".format(combined_plane))
00087         return combined_plane                    
00088 
00089 
00090 
00091 class Node:
00092     "Ros wrapper for the plane state estimator"
00093     
00094     def __init__(self):
00095         "Set up ros comms and initialize actual estimator"
00096         self.lock = threading.Lock()
00097         self.pe = PlaneSetEstimator(rospy.get_param("~max_plane_displacement", 0.1))
00098         with self.lock:
00099             self.sub = rospy.Subscriber('plane', msg.Plane, self.process_plane)
00100             self.pub = rospy.Publisher('planes', msg.Planes)
00101             self.vis_pub = rospy.Publisher('visualization_marker', vm.Marker)
00102             self.srv = rospy.Service('get_containing_plane', srv.PlaneExchange,
00103                                      self.get_containing_plane)
00104         LOG.info('Initialized node')
00105 
00106     def process_plane(self, p):
00107         LOG.debug("Processing plane")
00108         bp = pd.BoundedPlane(m)
00109         with self.lock:
00110             self.pe.process_plane(bp)
00111 
00112     def get_containing_plane(self, req):
00113         bp = pd.BoundedPlane(req.in_plane)
00114         LOG.debug("Getting containing plane for {0}".format(bp))
00115         with self.lock:
00116             return pd.to_plane_msg(self.pe.get_containing_plane(bp))
00117 
00118     def spin(self):
00119         "Publish current estimate at fixed rate"
00120         r = rospy.Rate(0.3)
00121         while not rospy.is_shutdown():
00122             time.sleep(2.0) # Temporary due to rosbag issues
00123             # r.sleep()
00124             with self.lock:
00125                 planes = self.pe.planes
00126                 self.pub.publish(map(pd.to_plane_msg, planes.values()))
00127                 if len(planes)>0:
00128                     self.vis_pub.publish(pd.to_marker(planes.values(), rospy.Time.now()))
00129 
00130 
00131 
00132 def main():
00133     rospy.init_node('plane_set_estimator')
00134     node = Node()
00135     node.spin()
00136 
00137 if __name__ == "__main__":
00138     main()


semanticmodel
Author(s): Julian ("Mac") Mason
autogenerated on Thu Dec 12 2013 12:39:10