dsr_service_io_basic.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 # ##
4 # @brief [py example basic] 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 from std_msgs.msg import String,Int32,Int32MultiArray,Float64,Float64MultiArray,MultiArrayLayout,MultiArrayDimension
11 import sys
12 sys.dont_write_bytecode = True
13 #sys.path.append( os.path.abspath(os.path.join(os.path.dirname(__file__),"../../../../common/imp")) ) # get import pass : DSR_ROBOT.py
14 #from DSR_ROBOT import *
15 
16 from dsr_msgs.msg import *
17 from dsr_msgs.srv import *
18 
19 ROBOT_ID = "dsr01"
20 ROBOT_MODEL = "m1013"
21 
22 def SET_ROBOT(id, model):
23  ROBOT_ID = id; ROBOT_MODEL= model
24 
25 def shutdown():
26  print "shutdown time!"
27  print "shutdown time!"
28  print "shutdown time!"
29 
30  pub_stop.publish(stop_mode=1) #STOP_TYPE_QUICK)
31  return 0
32 
33 # convert list to Float64MultiArray
35  _res = []
36  for i in list_src:
37  item = Float64MultiArray()
38  item.data = i
39  _res.append(item)
40  #print(_res)
41  #print(len(_res))
42  return _res
43 
44 if __name__ == "__main__":
45  #----- set target robot ---------------
46  my_robot_id = "dsr01"
47  my_robot_model = "m1013"
48  SET_ROBOT(my_robot_id, my_robot_model)
49 
50  rospy.init_node('dsr_service_io_basic_py')
51  rospy.on_shutdown(shutdown)
52 
53 
54  pub_stop = rospy.Publisher('/'+ROBOT_ID +ROBOT_MODEL+'/stop', RobotStop, queue_size=10)
55 
56  #print 'wait services'
57  #rospy.wait_for_service('/'+ROBOT_ID +ROBOT_MODEL+'/drl/drl_start')
58 
59  set_digital_output = rospy.ServiceProxy('/' + ROBOT_ID + ROBOT_MODEL + '/io/set_digital_output', SetCtrlBoxDigitalOutput)
60  get_digital_input = rospy.ServiceProxy('/' + ROBOT_ID + ROBOT_MODEL + '/io/get_digital_input', GetCtrlBoxDigitalInput)
61 
62  set_digital_output(2, True)
63  if get_digital_input(2) == 1 :
64  set_digital_output(11, True)
65 
66 
67  while not rospy.is_shutdown():
68  pass
69 
70  print 'good bye!'
def _ros_listToFloat64MultiArray(list_src)


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