receiver.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 """
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.
6 
7 Running from command line:
8  $ rosrun indoor_positioning receiver.py <TYPE> <REQUIRED> <OPTIONAL>
9  For example:
10  $ rosrun indoor_positioning receiver.py usb /dev/ttyUSB0
11  $ rosrun indoor_positioning receiver.py tcp 192.168.2.223
12 
13 Subscribed topics:
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
16 
17 Published topics:
18  - ips/receiver/raw (indoor_positioning/StringStamped):
19  Raw messages received from the receiver or USB stick
20 
21 Parameters:
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
30 """
31 
32 from __future__ import print_function
33 import rospy
34 from std_msgs.msg import String
35 from indoor_positioning.msg import StringStamped
38 
39 
41  """
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.
45  """
46  def __init__(self):
47  """Initialize IPS receiver class by passing the IP address the receiver or port the USB stick is connected to."""
48  # type of connected to receiver. Either 'tcp' for standard receiver or 'usb' for USB stick
49  self.type = rospy.get_param('~type') if rospy.has_param('~type') else 'tcp'
50  # required parameter for connection. IP address for standard receiver or USB port for USB stick
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
53  # initialize serial connection with USB stick or TCP connection with standard receiver
54  if self.type == 'usb':
55  self.baudrate = rospy.get_param('~baudrate') if rospy.has_param('~baudrate') else 115200
56  self.con = USBSerial(self.port, baudrate=self.baudrate)
57  elif self.type == 'tcp':
58  self.con = TCPSocket(self.host, port=int(self.port))
59  else:
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))
62 
63  # initialize subscriber that listens to ips/receiver/send to send messages to the receiver on callback
64  self.rec_send_sub = rospy.Subscriber('ips/receiver/send', String, self.callback)
65  # initialize publisher object
66  self.rec_pub = rospy.Publisher('ips/receiver/raw', StringStamped, queue_size=10)
67  # specify publishing rate
68  self.rate = rospy.Rate(30)
69 
70  def callback(self, msg):
71  """
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
74  """
75  self.con.send(msg.data)
76  print(msg.data)
77  # rospy.sleep(0.5)
78 
79  def publish(self):
80  """Publish raw receiver messages to the ips/receiver/raw topic."""
81  while not rospy.is_shutdown():
82  # get a single receiver message
83  line = self.con.get_line(b'\r')
84  # generate message
85  msg = StringStamped()
86  msg.header.stamp = rospy.Time.now()
87  msg.data = str(line)
88  # publish line as String message with timestamp
89  self.rec_pub.publish(msg)
90  # wait according to publishing rate
91  self.rate.sleep()
92 
93  def shutdown(self):
94  """Close USB connection on shutdown."""
95  self.con.close()
96 
97 
98 if __name__ == '__main__':
99  # start node
100  rospy.init_node('receiver', anonymous=True, disable_signals=True)
101  # initialize IPSReceiver class
102  ips = IPSReceiver()
103  try:
104  # publish receiver messages
105  ips.publish()
106  except rospy.ROSInterruptException:
107  pass
def shutdown(self)
Definition: receiver.py:93
def callback(self, msg)
Definition: receiver.py:70
def publish(self)
Definition: receiver.py:79
def __init__(self)
Definition: receiver.py:46


indoor_positioning
Author(s): Christian Arndt
autogenerated on Mon Jun 10 2019 13:33:13