single_robot_mobile.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 # ##
4 # @brief [py example gripper] gripper test for doosan robot
5 # @author Jin Hyuk Gong (jinhyuk.gong@doosan.com)
6 
7 import rospy
8 import os
9 import threading, time
10 import sys
11 import random
12 from geometry_msgs.msg import Twist
13 
14 sys.dont_write_bytecode = True
15 sys.path.append( os.path.abspath(os.path.join(os.path.dirname(__file__),"../../../../common/imp")) ) # get import pass : DSR_ROBOT.py
16 
17 # for single robot
18 ROBOT_ID = "dsr01"
19 ROBOT_MODEL = "m1013"
20 
21 RAND_MAX = 2147483647
22 
23 import DR_init
24 DR_init.__dsr__id = ROBOT_ID
25 DR_init.__dsr__model = ROBOT_MODEL
26 from DSR_ROBOT import *
27 
28 
30  msg = Twist()
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)
35 
36 def SET_ROBOT(id, model):
37  ROBOT_ID = id; ROBOT_MODEL= model
38 
39 def shutdown():
40  print "shutdown time!"
41  print "shutdown time!"
42  print "shutdown time!"
43 
44  pub_stop.publish(stop_mode=1) #STOP_TYPE_QUICK)
45  return 0
46 
47 # convert list to Float64MultiArray
49  _res = []
50  for i in list_src:
51  item = Float64MultiArray()
52  item.data = i
53  _res.append(item)
54  #print(_res)
55  #print(len(_res))
56  return _res
57 
58 if __name__ == "__main__":
59  #----- set target robot ---------------
60  my_robot_id = "dsr01"
61  my_robot_model = "m1013"
62  SET_ROBOT(my_robot_id, my_robot_model)
63 
64  rospy.init_node('single_robot_mobile_py')
65  rospy.on_shutdown(shutdown)
66 
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)
69 
70  mThread = threading.Thread(target = thread_mobile)
71  mThread.daemon = True
72  mThread.start()
73 
74  set_velx(30,20) # set global task speed: 30(mm/sec), 20(deg/sec)
75  set_accx(60,40) # set global task accel: 60(mm/sec2), 40(deg/sec2)
76 
77  velx=[50, 50]
78  accx=[100, 100]
79 
80  p1= posj(0,0,0,0,0,0) #joint
81  p2= posj(0.0, 0.0, 90.0, 0.0, 90.0, 0.0) #joint
82 
83  x1= posx(400, 500, 800.0, 0.0, 180.0, 0.0) #task
84  x2= posx(400, 500, 500.0, 0.0, 180.0, 0.0) #task
85 
86  c1 = posx(559,434.5,651.5,0,180,0)
87  c2 = posx(559,434.5,251.5,0,180,0)
88 
89 
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]
97 
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]
105 
106 
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)
116 
117 
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]
124 
125 
126 
127  while not rospy.is_shutdown():
128  movej(p2, vel=100, acc=100)
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)
137 
138 
139 
140  print 'good bye!'
def movej(fTargetPos, fTargetVel, fTargetAcc, fTargetTime=0.0, fBlendingRadius=0.0, nMoveMode=MOVE_MODE_ABSOLUTE, nBlendingType=BLENDING_SPEED_TYPE_DUPLICATE, nSyncType=0)
def SET_ROBOT(id, model)
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)


py
Author(s):
autogenerated on Sat May 18 2019 02:32:56