3 This node publishes tf transforms between the frame_id set in the config file and the beacon positions in that zone. 4 You can use these transforms for visualization in rviz to make sure you have set up your environment correctly. 7 - beacon.frame_id -> beacon.eid 8 Transforms for all zones and beacons defined in the config file. Transforms are broadcasted from the zone 9 frame_id to the position of the beacon in that frame 12 - ~config_file (string, default='config/zones.yml'): 13 Path to the configuration file of zones and beacons relative to the package directory 14 - ~rate (double, default=0.1): 15 The publishing rate of transforms in transforms per second 21 from geometry_msgs.msg
import TransformStamped
27 Get all beacons from the configuration file and store them in a list. Then publish tf transforms for every beacon 28 from the zone's frame_id to the position of the beacon. 32 config_dir = rospy.get_param(
'~config_file')
if rospy.has_param(
'~config_file')
else 'config/zones.yml' 33 abs_dir = os.path.join(os.path.dirname(os.path.dirname(__file__)), config_dir)
39 for z
in positioning.zones:
41 self.beacons.append(b)
44 self.
br = tf2_ros.StaticTransformBroadcaster()
47 self.
rate = rospy.Rate(rospy.get_param(
'~rate'))
if rospy.has_param(
'~rate')
else rospy.Rate(0.1)
50 """Publish static tfs for beacon positions and zone polygons""" 51 tf = TransformStamped()
52 while not rospy.is_shutdown():
54 tf.header.stamp = rospy.Time.now()
56 tf.header.frame_id = b.frame_id
57 tf.child_frame_id = b.eid
59 tf.transform.translation.x = b.position[0]
60 tf.transform.translation.y = b.position[1]
61 tf.transform.translation.z = b.position[2]
63 tf.transform.rotation.x = 0
64 tf.transform.rotation.y = 0
65 tf.transform.rotation.z = 0
66 tf.transform.rotation.w = 1
68 self.br.sendTransform(tf)
74 if __name__ ==
'__main__':
76 rospy.init_node(
'ips_map', anonymous=
True)
82 except rospy.ROSInterruptException: