object_pick_and_place_simple.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 sys.dont_write_bytecode = True
12 sys.path.append( os.path.abspath(os.path.join(os.path.dirname(__file__),"../../../../common/imp")) ) # get import pass : DSR_ROBOT.py
13 
14 # for single robot
15 ROBOT_ID = "dsr01"
16 ROBOT_MODEL = "m1013"
17 import DR_init
18 DR_init.__dsr__id = ROBOT_ID
19 DR_init.__dsr__model = ROBOT_MODEL
20 from DSR_ROBOT import *
21 
24 
25 def robotiq_2f_move(width):
26  srv_robotiq_2f_move(width)
27 
28 def SET_ROBOT(id, model):
29  ROBOT_ID = id; ROBOT_MODEL= model
30 
31 def shutdown():
32  print "shutdown time!"
33  print "shutdown time!"
34  print "shutdown time!"
35 
36  pub_stop.publish(stop_mode=1) #STOP_TYPE_QUICK)
37  return 0
38 
39 # convert list to Float64MultiArray
41  _res = []
42  for i in list_src:
43  item = Float64MultiArray()
44  item.data = i
45  _res.append(item)
46  #print(_res)
47  #print(len(_res))
48  return _res
49 
50 if __name__ == "__main__":
51  #----- set target robot ---------------
52  my_robot_id = "dsr01"
53  my_robot_model = "m1013"
54  SET_ROBOT(my_robot_id, my_robot_model)
55 
56  rospy.init_node('pick_and_place_simple_py')
57  rospy.on_shutdown(shutdown)
58 
59 
60  pub_stop = rospy.Publisher('/'+ROBOT_ID +ROBOT_MODEL+'/stop', RobotStop, queue_size=10)
61  srv_robotiq_2f_open = rospy.ServiceProxy('/' + ROBOT_ID + ROBOT_MODEL + '/gripper/robotiq_2f_open', Robotiq2FOpen)
62  srv_robotiq_2f_move = rospy.ServiceProxy('/' + ROBOT_ID + ROBOT_MODEL + '/gripper/robotiq_2f_move', Robotiq2FMove)
63 
64  p0 = posj(0, 0, 0, 0, 0, 0)
65  p1 = posj(0, 0, 90, 0, 90, 0)
66  p2 = posj(180, 0, 90, 0, 90, 0)
67 
68  x1 = posx(0, 0, -200, 0, 0, 0)
69  x2 = posx(0, 0, 200, 0, 0, 0)
70  velx = [50, 50]
71  accx = [100, 100]
72 
73  while not rospy.is_shutdown():
74  movej(p0, vel=60, acc=30)
75 
76  movej(p1, vel=60, acc=30)
77 
78  movel(x1, velx, accx, 2, 0, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE)
79  robotiq_2f_move(0.4)
80  rospy.sleep(1)
81  movel(x2, velx, accx, 2, 0, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE)
82 
83  movej(p2, vel=60, acc=30)
84 
85  movel(x1, velx, accx, 2, 0, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE)
87  rospy.sleep(1)
88  movel(x2, velx, accx, 2, 0, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE)
89 
90 
91 
92  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 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)


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