Go to the documentation of this file.00001
00002
00003 """Clear a region specified by a global axis-aligned bounding box in stored
00004 OctoMap.
00005
00006 """
00007
00008 import sys
00009 from time import sleep
00010
00011 import roslib
00012 roslib.load_manifest('octomap_server')
00013 from geometry_msgs.msg import Point
00014 import octomap_msgs.srv
00015 import rospy
00016
00017
00018 SRV_NAME = '/octomap_server/clear_bbx'
00019 SRV_INTERFACE = octomap_msgs.srv.BoundingBoxQuery
00020
00021
00022 if __name__ == '__main__':
00023 min = Point(*[float(x) for x in sys.argv[1:4]])
00024 max = Point(*[float(x) for x in sys.argv[4:7]])
00025
00026 rospy.init_node('octomap_eraser_cli', anonymous=True)
00027 sleep(1)
00028 service = rospy.ServiceProxy(SRV_NAME, SRV_INTERFACE)
00029 rospy.loginfo("Connected to %s service." % SRV_NAME)
00030
00031 service(min, max)