dsr_service_modbus_simple.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 # ##
4 # @brief [py example simple] motion basic test for doosan robot
5 # @author Kab Kyoum Kim (kabkyoum.kim@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 
16 ROBOT_SYSTEM_VIRTUAL = 1
17 ROBOT_SYSTEM_REAL = 0
18 ROBOT_ID = "dsr01"
19 ROBOT_MODEL = "m1013"
20 import DR_init
21 DR_init.__dsr__id = ROBOT_ID
22 DR_init.__dsr__model = ROBOT_MODEL
23 from DSR_ROBOT import *
24 
25 def shutdown():
26  print "shutdown time!"
27  print "shutdown time!"
28  print "shutdown time!"
29 
30  pub_stop.publish(stop_mode=STOP_TYPE_QUICK)
31  return 0
32 
34  msgRobotState_cb.count += 1
35 
36  if (0==(msgRobotState_cb.count % 100)):
37  rospy.loginfo("________ ROBOT STATUS ________")
38  print(" robot_state : %d" % (msg.robot_state))
39  print(" robot_state_str : %s" % (msg.robot_state_str))
40  print(" current_posj : %7.3f %7.3f %7.3f %7.3f %7.3f %7.3f" % (msg.current_posj[0],msg.current_posj[1],msg.current_posj[2],msg.current_posj[3],msg.current_posj[4],msg.current_posj[5]))
41  #print(" current_posx : %7.3f %7.3f %7.3f %7.3f %7.3f %7.3f" % (msg.current_posx[0],msg.current_posx[1],msg.current_posx[2],msg.current_posx[3],msg.current_posx[4],msg.current_posx[5]))
42 
43  #print(" io_control_box : %d" % (msg.io_control_box))
44 
49  print(" speed : %d" % (msg.speed))
50  #print(" mastering_need : %d" % (msg.mastering_need))
51  #print(" drl_stopped : %d" % (msg.drl_stopped))
52  #print(" disconnected : %d" % (msg.disconnected))
53 msgRobotState_cb.count = 0
54 
56  rospy.Subscriber('/'+ROBOT_ID +ROBOT_MODEL+'/state', RobotState, msgRobotState_cb)
57  rospy.spin()
58  #rospy.spinner(2)
59 
60 if __name__ == "__main__":
61  rospy.init_node('dsr_simple_test_py')
62  rospy.on_shutdown(shutdown)
63 
64  t1 = threading.Thread(target=thread_subscriber)
65  t1.daemon = True
66  t1.start()
67 
68  pub_stop = rospy.Publisher('/'+ROBOT_ID +ROBOT_MODEL+'/stop', RobotStop, queue_size=10)
69 
70  add_modbus_signal("di1","192.168.137.50", 502, MODBUS_REGISTER_TYPE_DISCRETE_INPUTS, 3)
71  add_modbus_signal("do1", "192.168.137.50", 502, MODBUS_REGISTER_TYPE_COILS, 3)
72  add_modbus_signal("ro1", "192.168.137.50", 502, MODBUS_REGISTER_TYPE_HOLDING_REGISTER, 7)
73  add_modbus_signal("ro2", "192.168.137.50", 502, MODBUS_REGISTER_TYPE_HOLDING_REGISTER, 6)
74 
75  while not rospy.is_shutdown():
76  set_modbus_output("ro2", 80)
77  set_modbus_output("do1", 1)
78 
79  if get_modbus_input("di1") == 1:
80  set_modbus_output("ro1", 30)
81 
82  print 'good bye!'


py
Author(s):
autogenerated on Thu Jun 20 2019 19:43:32