10 from std_msgs.msg
import String,Int32,Int32MultiArray,Float64,Float64MultiArray,MultiArrayLayout,MultiArrayDimension
12 sys.dont_write_bytecode =
True 22 ROBOT_ID = id; ROBOT_MODEL= model
25 print "shutdown time!" 26 print "shutdown time!" 27 print "shutdown time!" 29 pub_stop.publish(stop_mode=1)
36 item = Float64MultiArray()
43 if __name__ ==
"__main__":
46 my_robot_model =
"m1013" 49 rospy.init_node(
'single_robot_basic_py')
50 rospy.on_shutdown(shutdown)
53 pub_stop = rospy.Publisher(
'/'+ROBOT_ID +ROBOT_MODEL+
'/stop', RobotStop, queue_size=10)
58 move_joint = rospy.ServiceProxy(
'/'+ROBOT_ID +ROBOT_MODEL+
'/motion/move_joint', MoveJoint)
59 move_jointx = rospy.ServiceProxy(
'/'+ROBOT_ID +ROBOT_MODEL+
'/motion/move_jointx', MoveJointx)
61 move_line = rospy.ServiceProxy(
'/'+ROBOT_ID +ROBOT_MODEL+
'/motion/move_line', MoveLine)
62 move_circle = rospy.ServiceProxy(
'/'+ROBOT_ID +ROBOT_MODEL+
'/motion/move_circle', MoveCircle)
63 move_spline_joint = rospy.ServiceProxy(
'/'+ROBOT_ID +ROBOT_MODEL+
'/motion/move_spline_joint', MoveSplineJoint)
64 move_spline_task = rospy.ServiceProxy(
'/'+ROBOT_ID +ROBOT_MODEL+
'/motion/move_spline_task', MoveSplineTask)
66 move_blending = rospy.ServiceProxy(
'/'+ROBOT_ID +ROBOT_MODEL+
'/motion/move_blending', MoveBlending)
67 move_spiral = rospy.ServiceProxy(
'/'+ROBOT_ID +ROBOT_MODEL+
'/motion/move_spiral', MoveSpiral)
68 move_periodic = rospy.ServiceProxy(
'/'+ROBOT_ID +ROBOT_MODEL+
'/motion/move_periodic', MovePeriodic)
70 time= 0.0; mode=0; ref=0; radius=0.0; blendType=0; syncType=0
72 angle1=0.0; angle2=0.0
76 p2=[0.0, 0.0, 90.0, 0.0, 90.0, 0.0]
77 x1=[400, 500, 800.0, 0.0, 180.0, 0.0]
78 x2=[400, 500, 500.0, 0.0, 180.0, 0.0]
82 c1 = [559,434.5,651.5,0,180,0]
83 c2 = [559,434.5,251.5,0,180,0]
87 q1 =[10, -10, 20, -30, 10, 20]
88 q2 =[25, 0, 10, -50, 20, 40]
89 q3 =[50, 50, 50, 50, 50, 50]
90 q4 =[30, 10, 30, -20, 10, 60]
91 q5 =[20, 20, 40, 20, 0, 90]
94 x1 = [600, 600, 600, 0, 175, 0]
95 x2 = [600, 750, 600, 0, 175, 0]
96 x3 = [150, 600, 450, 0, 175, 0]
97 x4 = [-300, 300, 300, 0, 175, 0]
98 x5 = [-200, 700, 500, 0, 175, 0]
99 x6 = [600, 600, 400, 0, 175, 0]
109 period=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0]
114 bx11 = [370.1, 670.1, 650.1, 0.1, 180.1, 0.1]; bx12 = [370.1, 670.1, 650.1, 0.1, 180.1, 0.1]; bx_type1= [0]; bx_radius1=[21.0]
115 bx21 = [370.2, 670.2, 400.2, 0.2, 180.2, 0.2]; bx22 = [370.2, 545.2, 400.2, 0.2, 180.2, 0.2]; bx_type2= [1]; bx_radius2=[22.0]
116 bx31 = [370.3, 595.3, 400.3, 0.3, 180.3, 0.3]; bx32 = [370.3, 595.3, 400.3, 0.3, 180.3, 0.3]; bx_type3= [0]; bx_radius3=[23.0]
118 seg1 = bx11 + bx12 + bx_type1 + bx_radius1
119 seg2 = bx21 + bx22 + bx_type2 + bx_radius2
120 seg3 = bx31 + bx32 + bx_type3 + bx_radius3
125 while not rospy.is_shutdown():
126 move_joint(p2, vel, acc, time, radius, mode, blendType, syncType)
127 move_jointx(x1, sol, vel, acc, time, radius, ref, mode, blendType, syncType)
128 move_line(x2, velx, accx, time, radius, ref, mode, blendType, syncType)
129 move_circle(CirclePos, velx, accx, time, radius, ref, mode, angle1, angle2, blendType, syncType)
131 move_spline_task(SplinePosx, len(SplinePosx), velx, accx, time, ref, mode, opt, syncType)
132 move_spiral(revolution, maxRadius, maxLength, velx, accx, time, taskAxis, ref, syncType)
134 move_blending(mb_seg, posCnt, velx, accx, time, ref, mode, syncType)
def _ros_listToFloat64MultiArray(list_src)