test_comm.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import roslib; roslib.load_manifest('ur_driver')
00003 import time, sys, threading, math
00004 import copy
00005 import datetime
00006 import socket, select
00007 import struct
00008 import traceback, code
00009 import SocketServer
00010 
00011 import rospy
00012 
00013 from sensor_msgs.msg import JointState
00014 from ur_driver.deserialize import RobotState
00015 from ur_msgs.msg import *
00016 
00017 # renaming classes
00018 DigitalIn = Digital
00019 DigitalOut = Digital
00020 Flag  = Digital
00021 
00022 MULT_analog = 1000000.0
00023 MULT_analog_robotstate = 0.1
00024 
00025 joint_names = ['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint',
00026                'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']
00027 joint_offsets = {}
00028 
00029 
00030 def __on_packet(buf):
00031     state = RobotState.unpack(buf)
00032     
00033     mb_msg = MasterboardDataMsg()
00034     mb_msg.digital_input_bits = state.masterboard_data.digital_input_bits
00035     mb_msg.digital_output_bits = state.masterboard_data.digital_output_bits
00036     mb_msg.analog_input_range0 = state.masterboard_data.analog_input_range0
00037     mb_msg.analog_input_range1 = state.masterboard_data.analog_input_range1
00038     mb_msg.analog_input0 = state.masterboard_data.analog_input0
00039     mb_msg.analog_input1 = state.masterboard_data.analog_input1
00040     mb_msg.analog_output_domain0 = state.masterboard_data.analog_output_domain0
00041     mb_msg.analog_output_domain1 = state.masterboard_data.analog_output_domain1
00042     mb_msg.analog_output0 = state.masterboard_data.analog_output0
00043     mb_msg.analog_output1 = state.masterboard_data.analog_output1
00044     mb_msg.masterboard_temperature = state.masterboard_data.masterboard_temperature
00045     mb_msg.robot_voltage_48V = state.masterboard_data.robot_voltage_48V
00046     mb_msg.robot_current = state.masterboard_data.robot_current
00047     mb_msg.master_io_current = state.masterboard_data.master_io_current
00048     mb_msg.master_safety_state = state.masterboard_data.master_safety_state
00049     mb_msg.master_onoff_state = state.masterboard_data.master_onoff_state
00050     pub_masterboard_state.publish(mb_msg)
00051     
00052     
00053     # Use information from the robot state packet to publish IOStates        
00054     msg = IOStates()
00055     #gets digital in states
00056     for i in range(0, 10):
00057         msg.digital_in_states.append(DigitalIn(i, (state.masterboard_data.digital_input_bits & (1<<i))>>i))
00058     #gets digital out states
00059     for i in range(0, 10):
00060         msg.digital_out_states.append(DigitalOut(i, (state.masterboard_data.digital_output_bits & (1<<i))>>i))
00061     #gets analog_in[0] state
00062     inp = state.masterboard_data.analog_input0 / MULT_analog_robotstate
00063     msg.analog_in_states.append(Analog(0, inp))
00064     #gets analog_in[1] state
00065     inp = state.masterboard_data.analog_input1 / MULT_analog_robotstate
00066     msg.analog_in_states.append(Analog(1, inp))      
00067     #gets analog_out[0] state
00068     inp = state.masterboard_data.analog_output0 / MULT_analog_robotstate
00069     msg.analog_out_states.append(Analog(0, inp))     
00070     #gets analog_out[1] state
00071     inp = state.masterboard_data.analog_output1 / MULT_analog_robotstate
00072     msg.analog_out_states.append(Analog(1, inp))     
00073     #print "Publish IO-Data from robot state data"
00074     pub_io_states.publish(msg)
00075     
00076     # Notes: 
00077     # - Where are the flags coming from? Do we need flags? No, as 'prog' does not use them and other scripts are not running!
00078     # - analog_input2 and analog_input3 are within ToolData
00079     # - What to do with the different analog_input/output_range/domain?
00080     # - Shall we have appropriate ur_msgs definitions in order to reflect MasterboardData, ToolData,...?
00081 
00082 
00083 
00084 
00085 
00086 def main():
00087     rospy.init_node('test_comm', disable_signals=True)
00088     
00089     global pub_masterboard_state
00090     pub_masterboard_state = rospy.Publisher('masterboard_state', MasterboardDataMsg)
00091     global pub_io_states
00092     pub_io_states = rospy.Publisher('io_states', IOStates)
00093     
00094     
00095     robot_hostname = '192.168.0.42'
00096     port = 30002
00097     
00098     test_socket = socket.create_connection((robot_hostname, port))
00099     buf = ""
00100     
00101     while not rospy.is_shutdown():
00102         more = test_socket.recv(4096)
00103         if more:
00104             buf = buf + more
00105 
00106             # Attempts to extract a packet
00107             packet_length = struct.unpack_from("!i", buf)[0]
00108             print("PacketLength: ", packet_length, "; BufferSize: ", len(buf))
00109             if len(buf) >= packet_length:
00110                 packet, buf = buf[:packet_length], buf[packet_length:]
00111                 __on_packet(packet)
00112         else:
00113             print("There is no more...")
00114     
00115     test_socket.close()
00116 
00117 
00118 
00119 
00120 if __name__ == '__main__': main()


ur_driver
Author(s): Stuart Glaser, Shaun Edwards , Felix Messmer
autogenerated on Fri Aug 28 2015 13:31:30