3 Random Walk Example Code     5 Written by: Zahi Kakish (zmk5)    11 from geometry_msgs.msg 
import Twist
    12 from pheeno_robot 
import PheenoRobot
    16     """ Get arguments from rosrun for individual deployment. """    17     parser = argparse.ArgumentParser(
    18         description=
"Obstacle avoidance python script."    22     parser.add_argument(
"-n", 
"--number",
    25                         help=
"Add a pheeno number namespace.",
    30     return parser.parse_args(rospy.myargv()[1:])
    37     In this demo task, the Pheeno robot undergoes 3 count turn in a    38     specific direction followed by a 12 count linear motion. At 15    39     count the direction, the count is reset and a new direction is    45     if input_args.number == 
"":
    49         pheeno_number = str(input_args.number)
    52     rospy.init_node(
"pheeno_random_walk")
    65     while not rospy.is_shutdown():
    67             cmd_vel_msg.linear.x = 0
    68             cmd_vel_msg.angular.z = pheeno.random_turn() * angular_vel
    72             cmd_vel_msg.linear.x = linear_vel
    73             cmd_vel_msg.angular.z = 0
    82         pheeno.publish_cmd_vel(cmd_vel_msg)
    87 if __name__ == 
"__main__":
    91     except rospy.ROSInterruptException:
    95         rospy.loginfo(
"Exiting 'pheeno_random_walk' node.")