3 Use this node to establish a connection with the metraTec IPS receiver or USB stick. You have to pass the USB port the 4 stick is connected to or the IP address of the regular receiver as a command line argument or as a private parameter 5 when you are using a launch file. 7 Running from command line: 8 $ rosrun indoor_positioning receiver.py <TYPE> <REQUIRED> <OPTIONAL> 10 $ rosrun indoor_positioning receiver.py usb /dev/ttyUSB0 11 $ rosrun indoor_positioning receiver.py tcp 192.168.2.223 14 - ips/receiver/send (std_msgs/String): 15 Message to be sent over the TCP or serial connection to the IPS receiver or USB stick 18 - ips/receiver/raw (indoor_positioning/StringStamped): 19 Raw messages received from the receiver or USB stick 22 - ~type (string, default='tcp'): 23 'tcp' for TCP receiver or 'usb' for metraTec USB stick 24 - ~host (string, default='192.168.2.223): 25 IP address of the connected receiver 26 - ~port (with type='tcp': int, default=10001; with type='usb': string, default='/dev/ttyUSB0): 27 Port for the TCP connection if '~type' parameter is set to 'tcp', otherwise specifies the USB port of the stick 28 - ~baudrate (int, default=115200): 29 Baudrate to use for serial communication with USB receiver 32 from __future__
import print_function
34 from std_msgs.msg
import String
35 from indoor_positioning.msg
import StringStamped
42 Use this class to establish a connection with the metraTec IPS receiver or USB stick and publish the received 43 messages to the ips/receiver/raw topic. The node also listens to the ips/receiver/send topic and invokes a 44 callback that forwards these messages to the connected receiver when it is updated. 47 """Initialize IPS receiver class by passing the IP address the receiver or port the USB stick is connected to.""" 49 self.
type = rospy.get_param(
'~type')
if rospy.has_param(
'~type')
else 'tcp' 51 self.
host = rospy.get_param(
'~host')
if rospy.has_param(
'~host')
else '192.168.2.223' 52 self.
port = rospy.get_param(
'~port')
if rospy.has_param(
'~port')
else 10001
54 if self.
type ==
'usb':
55 self.
baudrate = rospy.get_param(
'~baudrate')
if rospy.has_param(
'~baudrate')
else 115200
57 elif self.
type ==
'tcp':
60 print(
'Connection type "{}" is invalid. Shutting down node!'.format(self.
type))
61 rospy.signal_shutdown(
'Connection type "{}" is invalid. Shutting down node!'.format(self.
type))
66 self.
rec_pub = rospy.Publisher(
'ips/receiver/raw', StringStamped, queue_size=10)
72 Send message to connected device when /ips/receiver/send topic is updated. 73 :param msg: String: message to be sent to the connected device 75 self.con.send(msg.data)
80 """Publish raw receiver messages to the ips/receiver/raw topic.""" 81 while not rospy.is_shutdown():
83 line = self.con.get_line(b
'\r')
86 msg.header.stamp = rospy.Time.now()
89 self.rec_pub.publish(msg)
94 """Close USB connection on shutdown.""" 98 if __name__ ==
'__main__':
100 rospy.init_node(
'receiver', anonymous=
True, disable_signals=
True)
106 except rospy.ROSInterruptException: