random_walk.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 """
00003 Random Walk Example Code
00004 
00005 Written by: Zahi Kakish (zmk5)
00006 License: BSD 3-Clause
00007 
00008 """
00009 import argparse
00010 import rospy
00011 from geometry_msgs.msg import Twist
00012 from pheeno_robot import PheenoRobot
00013 
00014 
00015 def get_args():
00016     """ Get arguments from rosrun for individual deployment. """
00017     parser = argparse.ArgumentParser(
00018         description="Obstacle avoidance python script."
00019     )
00020 
00021     # Required arguments
00022     parser.add_argument("-n", "--number",
00023                         action="store",
00024                         required=False,
00025                         help="Add a pheeno number namespace.",
00026                         default="")
00027 
00028     # The rationale behind rospy.myargv()[1:] is provided here:
00029     # https://groups.google.com/a/rethinkrobotics.com/forum/#!topic/brr-users/ErXVWhRmtNA
00030     return parser.parse_args(rospy.myargv()[1:])
00031 
00032 
00033 def main():
00034     """
00035     Random Walk Pheeno
00036 
00037     In this demo task, the Pheeno robot undergoes 3 count turn in a
00038     specific direction followed by a 12 count linear motion. At 15
00039     count the direction, the count is reset and a new direction is
00040     chosen.
00041 
00042     """
00043     # Get arguments from argument parser.
00044     input_args = get_args()
00045     if input_args.number == "":
00046         pheeno_number = ""
00047 
00048     else:
00049         pheeno_number = str(input_args.number)
00050 
00051     # Initialize Node
00052     rospy.init_node("pheeno_random_walk")
00053 
00054     # Create PheenoRobot Object
00055     pheeno = PheenoRobot(pheeno_number, 0.05, 0)
00056 
00057     # Other Important Variables
00058     count = 0
00059     cmd_vel_msg = Twist()
00060     linear_vel = 0.05
00061     angular_vel = 0.07
00062 
00063     rate = rospy.Rate(15)
00064 
00065     while not rospy.is_shutdown():
00066         if count == 0:
00067             cmd_vel_msg.linear.x = 0
00068             cmd_vel_msg.angular.z = pheeno.random_turn() * angular_vel
00069             count += 1
00070 
00071         elif count == 3:
00072             cmd_vel_msg.linear.x = linear_vel
00073             cmd_vel_msg.angular.z = 0
00074             count += 1
00075 
00076         elif count == 15:
00077             count = 0
00078 
00079         else:
00080             count += 1
00081 
00082         pheeno.publish_cmd_vel(cmd_vel_msg)
00083         rate.sleep()
00084 
00085 
00086 
00087 if __name__ == "__main__":
00088     try:
00089         main()
00090 
00091     except rospy.ROSInterruptException:
00092         pass
00093 
00094     finally:
00095         rospy.loginfo("Exiting 'pheeno_random_walk' node.")


pheeno_ros
Author(s): Zahi Kakish, Sean Wilson
autogenerated on Thu Jun 6 2019 21:26:16