11 sys.dont_write_bytecode =
True 12 sys.path.append( os.path.abspath(os.path.join(os.path.dirname(__file__),
"../../../../common/imp")) )
16 ROBOT_SYSTEM_VIRTUAL = 1
21 DR_init.__dsr__id = ROBOT_ID
22 DR_init.__dsr__model = ROBOT_MODEL
23 from DSR_ROBOT
import *
26 print "shutdown time!" 27 print "shutdown time!" 28 print "shutdown time!" 30 pub_stop.publish(stop_mode=STOP_TYPE_QUICK)
34 msgRobotState_cb.count += 1
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]))
49 print(
" speed : %d" % (msg.speed))
53 msgRobotState_cb.count = 0
56 rospy.Subscriber(
'/'+ROBOT_ID +ROBOT_MODEL+
'/state', RobotState, msgRobotState_cb)
60 if __name__ ==
"__main__":
61 rospy.init_node(
'dsr_simple_test_py')
62 rospy.on_shutdown(shutdown)
64 t1 = threading.Thread(target=thread_subscriber)
68 pub_stop = rospy.Publisher(
'/'+ROBOT_ID +ROBOT_MODEL+
'/stop', RobotStop, queue_size=10)
73 while not rospy.is_shutdown():
def msgRobotState_cb(msg)