Go to the documentation of this file.00001
00002 import roslib; roslib.load_manifest('kobuki_testsuite')
00003 import rospy
00004
00005 from kobuki_testsuite import SafeWandering
00006
00007 if __name__ == '__main__':
00008
00009 cmdvel_topic = '/mobile_base/commands/velocity'
00010 odom_topic = '/odom'
00011 bump_topic = '/mobile_base/events/bumper'
00012 cliff_topic = '/mobile_base/events/cliff'
00013 rospy.init_node('safe_wandering')
00014
00015 wanderer = SafeWandering(cmdvel_topic,odom_topic, bump_topic, cliff_topic)
00016
00017 rospy.loginfo("Starting to wander")
00018 wanderer.init(0.1,-0.1, 1.65)
00019 wanderer.execute()
00020 rospy.loginfo("Stopping wandering")
00021 wanderer.stop()
00022