12 from geometry_msgs.msg
import Twist
14 sys.dont_write_bytecode =
True 15 sys.path.append( os.path.abspath(os.path.join(os.path.dirname(__file__),
"../../../../common/imp")) )
24 DR_init.__dsr__id = ROBOT_ID
25 DR_init.__dsr__model = ROBOT_MODEL
26 from DSR_ROBOT
import *
31 while not rospy.is_shutdown():
32 msg.linear.x = (random.random())/RAND_MAX + 1
33 msg.angular.z = 2*(random.random())/RAND_MAX - 1
34 pubMobile.publish(msg)
37 ROBOT_ID = id; ROBOT_MODEL= model
40 print "shutdown time!" 41 print "shutdown time!" 42 print "shutdown time!" 44 pub_stop.publish(stop_mode=1)
51 item = Float64MultiArray()
58 if __name__ ==
"__main__":
61 my_robot_model =
"m1013" 64 rospy.init_node(
'single_robot_mobile_py')
65 rospy.on_shutdown(shutdown)
67 pub_stop = rospy.Publisher(
'/'+ROBOT_ID +ROBOT_MODEL+
'/stop', RobotStop, queue_size=10)
68 pubMobile = rospy.Publisher(
'/'+ROBOT_ID +
'/twist_marker_server/cmd_vel', Twist, queue_size=10)
70 mThread = threading.Thread(target = thread_mobile)
81 p2= posj(0.0, 0.0, 90.0, 0.0, 90.0, 0.0)
83 x1= posx(400, 500, 800.0, 0.0, 180.0, 0.0)
84 x2= posx(400, 500, 500.0, 0.0, 180.0, 0.0)
86 c1 = posx(559,434.5,651.5,0,180,0)
87 c2 = posx(559,434.5,251.5,0,180,0)
90 q0 = posj(0,0,0,0,0,0)
91 q1 = posj(10, -10, 20, -30, 10, 20)
92 q2 = posj(25, 0, 10, -50, 20, 40)
93 q3 = posj(50, 50, 50, 50, 50, 50)
94 q4 = posj(30, 10, 30, -20, 10, 60)
95 q5 = posj(20, 20, 40, 20, 0, 90)
96 qlist = [q0, q1, q2, q3, q4, q5]
98 x1 = posx(600, 600, 600, 0, 175, 0)
99 x2 = posx(600, 750, 600, 0, 175, 0)
100 x3 = posx(150, 600, 450, 0, 175, 0)
101 x4 = posx(-300, 300, 300, 0, 175, 0)
102 x5 = posx(-200, 700, 500, 0, 175, 0)
103 x6 = posx(600, 600, 400, 0, 175, 0)
104 xlist = [x1, x2, x3, x4, x5, x6]
107 X1 = posx(370, 670, 650, 0, 180, 0)
108 X1a = posx(370, 670, 400, 0, 180, 0)
109 X1a2= posx(370, 545, 400, 0, 180, 0)
110 X1b = posx(370, 595, 400, 0, 180, 0)
111 X1b2= posx(370, 670, 400, 0, 180, 0)
112 X1c = posx(370, 420, 150, 0, 180, 0)
113 X1c2= posx(370, 545, 150, 0, 180, 0)
114 X1d = posx(370, 670, 275, 0, 180, 0)
115 X1d2= posx(370, 795, 150, 0, 180, 0)
118 seg11 =
posb(DR_LINE, X1, radius=20)
119 seg12 =
posb(DR_CIRCLE, X1a, X1a2, radius=21)
120 seg14 =
posb(DR_LINE, X1b2, radius=20)
121 seg15 =
posb(DR_CIRCLE, X1c, X1c2, radius=22)
122 seg16 =
posb(DR_CIRCLE, X1d, X1d2, radius=23)
123 b_list1 = [seg11, seg12, seg14, seg15, seg16]
127 while not rospy.is_shutdown():
129 movejx(x1, vel=30, acc=60)
130 movel(x2, velx, accx)
131 movec(c1, c2, velx, accx)
132 movesj(qlist, vel=100, acc=100)
133 movesx(xlist, vel=100, acc=100)
134 move_spiral(rev=9.5,rmax=20.0,lmax=50.0,time=20.0,axis=DR_AXIS_Z,ref=DR_TOOL)
135 move_periodic(amp =[10,0,0,0,30,0], period=1.0, atime=0.2, repeat=5, ref=DR_TOOL)
136 moveb(b_list1, vel=150, acc=250, ref=DR_BASE, mod=DR_MV_MOD_ABS)
def movej(fTargetPos, fTargetVel, fTargetAcc, fTargetTime=0.0, fBlendingRadius=0.0, nMoveMode=MOVE_MODE_ABSOLUTE, nBlendingType=BLENDING_SPEED_TYPE_DUPLICATE, nSyncType=0)
def movesj(fTargetPos, nPosCount, fTargetVel, fTargetAcc, fTargetTime=0.0, nMoveMode=MOVE_MODE_ABSOLUTE, nSyncType=0)
def movejx(fTargetPos, fTargetVel, fTargetAcc, fTargetTime=0.0, fBlendingRadius=0.0, nMoveReference=MOVE_REFERENCE_BASE, nMoveMode=MOVE_MODE_ABSOLUTE, nBlendingType=BLENDING_SPEED_TYPE_DUPLICATE, nSolSpace=0, nSyncType=0)
def _ros_listToFloat64MultiArray(list_src)
def movel(fTargetPos, fTargetVel, fTargetAcc, fTargetTime=0.0, fBlendingRadius=0.0, nMoveReference=MOVE_REFERENCE_BASE, nMoveMode=MOVE_MODE_ABSOLUTE, nBlendingType=BLENDING_SPEED_TYPE_DUPLICATE, nSyncType=0)
def movesx(fTargetPos, nPosCount, fTargetVel, fTargetAcc, fTargetTime=0.0, nMoveMode=MOVE_MODE_ABSOLUTE, nMoveReference=MOVE_REFERENCE_BASE, nVelOpt=SPLINE_VELOCITY_OPTION_DEFAULT, nSyncType=0)
def moveb(fTargetPos, nPosCount, fTargetVel, fTargetAcc, fTargetTime=0.0, nMoveMode=MOVE_MODE_ABSOLUTE, nMoveReference=MOVE_REFERENCE_BASE, nSyncType=0)
def movec(fTargetPos, fTargetVel, fTargetAcc, fTargetTime=0.0, fBlendingRadius=0.0, nMoveReference=MOVE_REFERENCE_BASE, nMoveMode=MOVE_MODE_ABSOLUTE, fAngle1=0.0, fAngle2=0.0, nBlendingType=BLENDING_SPEED_TYPE_DUPLICATE, nSyncType=0)