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
00035
00036
00037
00038
00039 PKG = 'door_handle_detector'
00040
00041 import roslib; roslib.load_manifest(PKG)
00042
00043 import sys
00044 from optparse import OptionParser
00045 import tf
00046 import bullet
00047
00048 import rospy
00049 from sensor_msgs.msg import PointCloud, ChannelFloat32, Point32
00050 from geometry_msgs.msg import Point32
00051
00052 NAME='point_cloud_cropper'
00053
00054 class Cropper:
00055 def __init__(self, zmin, zmax, frame):
00056 self.zmin = zmin
00057 self.zmax = zmax
00058 self.frame = frame
00059 self.sub = rospy.Subscriber('full_cloud', PointCloud, self.cloud_cb)
00060 self.pub = rospy.Publisher('full_cloud_cropped', PointCloud)
00061 self.tf = tf.listener.TransformListener()
00062 rospy.init_node('cropper', anonymous=True)
00063
00064 def cloud_cb(self, msg):
00065 print 'Received message with %d points'%(len(msg.points))
00066 newmsg = PointCloud(msg.header,[],[])
00067 for c in msg.chan:
00068 newmsg.channels.append(ChannelFloat32(c.name,[]))
00069 for i in range(0,len(msg.points)):
00070 if self.frame is None:
00071 p = msg.points[i]
00072 else:
00073 tfp = tf.PointStamped(bullet.Vector3(msg.points[i].x, msg.points[i].y, msg.points[i].z), 0, 0, msg.header.frame_id)
00074 tfpprime = self.tf.transform_point(self.frame, tfp)
00075 p = Point32(tfpprime.point.x(), tfpprime.point.y(), tfpprime.point.z())
00076 if p.z >= self.zmin and p.z <= self.zmax:
00077 newmsg.points.append(p)
00078 for j in range(0,len(msg.chan)):
00079 newmsg.channels[j].values.append(msg.channels[j].values[i])
00080 print 'Publishing message with %d points'%(len(newmsg.points))
00081 self.pub.publish(newmsg)
00082
00083 if __name__ == "__main__":
00084
00085 parser = OptionParser(usage="usage: %prog [options]", prog=NAME)
00086 parser.add_option("", "--zmin",
00087 dest="zmin", default=None,
00088 help="Minimum z value to allow through")
00089 parser.add_option("", "--zmax",
00090 dest="zmax", default=None,
00091 help="Maximum z value to allow through")
00092 parser.add_option("-f", "--frame",
00093 dest="frame", default=None,
00094 help="Frame to transform to before cropping")
00095
00096 (options, args) = parser.parse_args(sys.argv)
00097 if options.zmin is None or options.zmax is None:
00098 parser.error("must specify both zmin and zmax")
00099 parser.print_help()
00100
00101 c = Cropper(float(options.zmin), float(options.zmax), options.frame)
00102 rospy.spin()