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. 8 - ips/receiver/raw (ros_ips/StringStamped): 9 Raw messages received by the UWB receiver 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 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 33 from geometry_msgs.msg
import PolygonStamped, Point32
34 from ros_ips.msg
import StringStamped
39 """Configure ROS node for metraTec IPS indoor positioning system for zone location.""" 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)
50 n_beacons = self.positioning.n_beacons
53 self.
buffer_length = rospy.get_param(
'~bcn_len')
if rospy.has_param(
'~bcn_len')
else 2*n_beacons
61 self.
zone_name_pub = rospy.Publisher(
'ips/receiver/current_zone/name', StringStamped, queue_size=1)
63 self.
zone_polygon_pub = rospy.Publisher(
'ips/receiver/current_zone/polygon', PolygonStamped, queue_size=1)
65 self.
zone_leave_pub = rospy.Publisher(
'ips/receiver/zone_leave', StringStamped, queue_size=10)
67 self.
zone_enter_pub = rospy.Publisher(
'ips/receiver/zone_enter', StringStamped, queue_size=10)
69 self.
rate = rospy.Rate(rospy.get_param(
'~rate'))
if rospy.has_param(
'~rate')
else rospy.Rate(1)
73 Append incoming messages to list of previous messages. 74 :param msg: String, message of subscribed topic 77 self.msg_buffer.append(msg.data)
85 """Publish zone information""" 88 while not rospy.is_shutdown():
94 event = StringStamped()
98 event.data = last_zone.name
99 self.zone_leave_pub.publish(event)
101 elif last_zone
is None:
102 event.data = zone.name
103 self.zone_enter_pub.publish(event)
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)
112 name = StringStamped()
114 name.header.frame_id = zone.frame_id
115 name.data = zone.name
116 self.zone_name_pub.publish(name)
118 polygon = PolygonStamped()
120 polygon.header.frame_id = zone.frame_id
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)
132 if __name__ ==
'__main__':
134 rospy.init_node(
'positioning', anonymous=
False)
140 except rospy.ROSInterruptException: