Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 import rospy
00032 from geometry_msgs.msg import Twist
00033
00034 def timer_callback(event):
00035 pub.publish(twist_output)
00036
00037 def simple_motion(twist, duration):
00038 global twist_output
00039
00040 opposite_twist = Twist()
00041 opposite_twist.linear.x = -twist.linear.x
00042 opposite_twist.linear.y = -twist.linear.y
00043 opposite_twist.angular.z = -twist.angular.z
00044
00045 if rospy.is_shutdown():
00046 return
00047
00048 twist_output = twist
00049 rospy.sleep(duration)
00050 twist_output = zero_twist
00051 rospy.sleep(1.0)
00052 twist_output = opposite_twist
00053 rospy.sleep(duration)
00054 twist_output = zero_twist
00055 rospy.sleep(1.0)
00056
00057 def motion_demo():
00058 global pub
00059 pub = rospy.Publisher('/mobility_base/cmd_vel', Twist, queue_size=1)
00060 rospy.init_node('motion_demo');
00061
00062 global zero_twist
00063 zero_twist = Twist()
00064 zero_twist.linear.x = 0
00065 zero_twist.linear.y = 0
00066 zero_twist.angular.z = 0
00067
00068 global twist_output
00069 twist_output = Twist()
00070
00071 rospy.Timer(rospy.Duration(0.1), timer_callback)
00072
00073 speed = 0.2
00074 dist = 1 / 3.28
00075 vel = Twist()
00076
00077
00078 vel.linear.x = 0
00079 vel.linear.y = 0
00080 vel.angular.z = 0.628
00081 simple_motion(vel, 10.2)
00082
00083
00084 vel.linear.x = speed
00085 vel.linear.y = 0
00086 vel.angular.z = 0
00087 simple_motion(vel, dist/speed)
00088
00089
00090 vel.linear.x = 0.707 * speed
00091 vel.linear.y = -0.707 * speed
00092 vel.angular.z = 0
00093 simple_motion(vel, dist/speed)
00094
00095
00096 vel.linear.x = 0
00097 vel.linear.y = -speed
00098 vel.angular.z = 0
00099 simple_motion(vel, dist/speed)
00100
00101
00102 vel.linear.x = -0.707 * speed
00103 vel.linear.y = -0.707 * speed
00104 vel.angular.z = 0
00105 simple_motion(vel, dist/speed)
00106
00107
00108 vel.linear.x = -speed
00109 vel.linear.y = 0
00110 vel.angular.z = 0
00111 simple_motion(vel, dist/speed)
00112
00113
00114 vel.linear.x = -0.707 * speed
00115 vel.linear.y = 0.707 * speed
00116 vel.angular.z = 0
00117 simple_motion(vel, dist/speed)
00118
00119
00120 vel.linear.x = 0
00121 vel.linear.y = speed
00122 vel.angular.z = 0
00123 simple_motion(vel, dist/speed)
00124
00125
00126 vel.linear.x = 0.707 * speed
00127 vel.linear.y = 0.707 * speed
00128 vel.angular.z = 0
00129 simple_motion(vel, dist/speed)
00130
00131 if __name__ == '__main__':
00132 motion_demo()