scripts/positioning.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 """
3 Use this node to perform indoor zone location using the metraTec IPS tracking system. Prerequisites for using this node
4 is a running receiver-node that handles communication with the receiver and thus with the beacons in the vicinity.
5 Also, make sure that you have defined your zones correctly in the YAML config file.
6 
7 Subscribed topics:
8  - ips/receiver/raw (ros_ips/StringStamped):
9  Raw messages received by the UWB receiver
10 
11 Published topics:
12  - ips/receiver/current_zone/name (ros_ips/StringStamped):
13  Name of the zone the receiver is currently in
14  - ips/receiver/current_zone/polygon (geometry_msgs/PolygonStamped):
15  Polygon comprising the current zone
16  - ips/receiver/zone_leave (ros_ips/StringStamped):
17  Name of the zone that the receiver has left. Is published at the moment a zone-leave occurs
18  - ips/receiver/zone_enter (ros_ips/StringStamped):
19  Name of the zone that the receiver has entered. Is published at the moment a zone-enter occurs
20 
21 Parameters:
22  - ~config_file (string, default='PKG_DIR/config/zones.yml'):
23  Path to the configuration file of zones and beacons relative to the package directory
24  - ~rate (double, default=1):
25  The publishing rate in messages per second
26  - ~bcn_len (int, default=2*number_of_beacons):
27  Buffer length for BCN messages
28 """
29 
30 import rospy
31 import os
32 import rospkg
33 from geometry_msgs.msg import PolygonStamped, Point32
34 from ros_ips.msg import StringStamped
35 from ros_ips.positioning import Positioning
36 
37 
38 class IPS:
39  """Configure ROS node for metraTec IPS indoor positioning system for zone location."""
40  def __init__(self):
41  # subscribe to raw messages from USB stick
42  self.receiver_sub = rospy.Subscriber('ips/receiver/raw', StringStamped, self.callback)
43 
44  # get directory of config file
45  config_dir = rospy.get_param('~config_file') if rospy.has_param('~config_file') else 'config/zones.yml'
46  abs_dir = os.path.join(rospkg.RosPack().get_path('ros_ips'), config_dir)
47  # initialize positioning class
48  self.positioning = Positioning(abs_dir)
49  # get number of beacons specified in zones.yml file for default buffer values
50  n_beacons = self.positioning.n_beacons
51 
52  # number of messages to keep
53  self.buffer_length = rospy.get_param('~bcn_len') if rospy.has_param('~bcn_len') else 2*n_beacons
54  # list of incoming messages
55  self.msg_buffer = []
56  # timestamp from last received message
57  self.last_time = None
58 
59  # publishers
60  # current zone name
61  self.zone_name_pub = rospy.Publisher('ips/receiver/current_zone/name', StringStamped, queue_size=1)
62  # polygon of current zone
63  self.zone_polygon_pub = rospy.Publisher('ips/receiver/current_zone/polygon', PolygonStamped, queue_size=1)
64  # zone leave event
65  self.zone_leave_pub = rospy.Publisher('ips/receiver/zone_leave', StringStamped, queue_size=10)
66  # zone enter event
67  self.zone_enter_pub = rospy.Publisher('ips/receiver/zone_enter', StringStamped, queue_size=10)
68  # set publishing rate
69  self.rate = rospy.Rate(rospy.get_param('~rate')) if rospy.has_param('~rate') else rospy.Rate(1)
70 
71  def callback(self, msg):
72  """
73  Append incoming messages to list of previous messages.
74  :param msg: String, message of subscribed topic
75  """
76  # append message to buffer
77  self.msg_buffer.append(msg.data)
78  # save time of last raw signal
79  self.last_time = msg.header.stamp
80  # delete oldest message if buffer is full
81  if len(self.msg_buffer) > self.buffer_length:
82  del(self.msg_buffer[0])
83 
84  def publish(self):
85  """Publish zone information"""
86  # last zone that the receiver was in
87  last_zone = None
88  while not rospy.is_shutdown():
89  # get the current zone
90  zone = self.positioning.get_zone(self.msg_buffer) if self.msg_buffer else None
91  # check if zone change occurred
92  if zone != last_zone:
93  # publish zone change event
94  event = StringStamped()
95  event.header.stamp = self.last_time
96  # only zone leave
97  if zone is None:
98  event.data = last_zone.name
99  self.zone_leave_pub.publish(event)
100  # only zone enter
101  elif last_zone is None:
102  event.data = zone.name
103  self.zone_enter_pub.publish(event)
104  # leave on zone and enter another
105  else:
106  event.data = last_zone.name
107  self.zone_leave_pub.publish(event)
108  event.data = zone.name
109  self.zone_enter_pub.publish(event)
110  if zone is not None:
111  # publish zone name
112  name = StringStamped()
113  name.header.stamp = self.last_time
114  name.header.frame_id = zone.frame_id
115  name.data = zone.name
116  self.zone_name_pub.publish(name)
117  # publish zone polygon
118  polygon = PolygonStamped()
119  polygon.header.stamp = self.last_time
120  polygon.header.frame_id = zone.frame_id
121  points = []
122  for p in zone.polygon:
123  points.append(Point32(p[0], p[1], p[2]))
124  polygon.polygon.points = points
125  self.zone_polygon_pub.publish(polygon)
126  # set current zone to last zone
127  last_zone = zone
128  # wait to start next iteration
129  self.rate.sleep()
130 
131 
132 if __name__ == '__main__':
133  # start node
134  rospy.init_node('positioning', anonymous=False)
135  # initialize IPSReceiver class
136  ips = IPS()
137  try:
138  # publish receiver messages
139  ips.publish()
140  except rospy.ROSInterruptException:
141  pass
def callback(self, msg)


ros_ips
Author(s): Christian Arndt
autogenerated on Sat May 12 2018 02:24:12