add_cylinder.py
Go to the documentation of this file.
00001 #
00002 # Copyright (c) 2010, Georgia Tech Research Corporation
00003 # All rights reserved.
00004 # 
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions are met:
00007 #     * Redistributions of source code must retain the above copyright
00008 #       notice, this list of conditions and the following disclaimer.
00009 #     * Redistributions in binary form must reproduce the above copyright
00010 #       notice, this list of conditions and the following disclaimer in the
00011 #       documentation and/or other materials provided with the distribution.
00012 #     * Neither the name of the Georgia Tech Research Corporation nor the
00013 #       names of its contributors may be used to endorse or promote products
00014 #       derived from this software without specific prior written permission.
00015 # 
00016 # THIS SOFTWARE IS PROVIDED BY GEORGIA TECH RESEARCH CORPORATION ''AS IS'' AND
00017 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 # DISCLAIMED. IN NO EVENT SHALL GEORGIA TECH BE LIABLE FOR ANY DIRECT, INDIRECT,
00020 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00021 # LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00022 # OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00023 # LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00024 # OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00025 # ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 #
00027 
00028 # Author: Advait Jain (advait@cc.gatech.edu), Healthcare Robotics Lab, Georgia Tech
00029 
00030 
00031 import roslib; roslib.load_manifest('arm_navigation_tutorials')
00032 import sys
00033 import rospy
00034 
00035 from mapping_msgs.msg import CollisionObject
00036 from mapping_msgs.msg import CollisionObjectOperation
00037 from geometric_shapes_msgs.msg import Shape
00038 from geometry_msgs.msg import Pose
00039 
00040 
00041 def add_cylinder(id, bottom, radius, height, frameid):
00042     cylinder_object = CollisionObject()
00043     cylinder_object.id = id
00044     cylinder_object.operation.operation = CollisionObjectOperation.ADD
00045     cylinder_object.header.frame_id = frameid
00046     cylinder_object.header.stamp = rospy.Time.now()
00047 
00048     shp = Shape()
00049     shp.type = Shape.CYLINDER
00050     shp.dimensions = [0, 0]
00051     shp.dimensions[0] = radius
00052     shp.dimensions[1] = height
00053 
00054     pose = Pose()
00055     pose.position.x = bottom[0]
00056     pose.position.y = bottom[1]
00057     pose.position.z = bottom[2] + height/2.
00058     pose.orientation.x = 0
00059     pose.orientation.y = 0
00060     pose.orientation.z = 0
00061     pose.orientation.w = 1
00062     cylinder_object.shapes.append(shp)
00063     cylinder_object.poses.append(pose)
00064 
00065     pub.publish(cylinder_object)
00066 
00067 
00068 if __name__ == '__main__':
00069     rospy.init_node('add_cylinder_python')
00070 
00071     pub = rospy.Publisher('collision_object', CollisionObject)
00072     rospy.sleep(2.)
00073 
00074     add_cylinder('pole', (0.6, -0.6, 0.), 0.1, 0.75, 'base_link')
00075     rospy.loginfo('Should have published')
00076     rospy.sleep(2.)
00077 
00078 
00079 


arm_navigation_tutorials
Author(s): Advait Jain
autogenerated on Wed Nov 27 2013 12:09:02