ips_map.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 """
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.
5 
6 Published tf's:
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
10 
11 Parameters:
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
16 """
17 
18 import os
19 import rospy
20 import tf2_ros
21 from geometry_msgs.msg import TransformStamped
22 from ros_ips.positioning import Positioning
23 
24 
25 class IPSMap:
26  """
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.
29  """
30  def __init__(self):
31  # get directory of config file
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)
34  # initialize positioning class
35  positioning = Positioning(abs_dir)
36 
37  # get all beacon objects
38  self.beacons = []
39  for z in positioning.zones:
40  for b in z.beacons:
41  self.beacons.append(b)
42 
43  # initialize transform broadcaster
44  self.br = tf2_ros.StaticTransformBroadcaster()
45 
46  # publishing rate
47  self.rate = rospy.Rate(rospy.get_param('~rate')) if rospy.has_param('~rate') else rospy.Rate(0.1)
48 
49  def publish(self):
50  """Publish static tfs for beacon positions and zone polygons"""
51  tf = TransformStamped()
52  while not rospy.is_shutdown():
53  # publish transforms for all positions
54  tf.header.stamp = rospy.Time.now()
55  for b in self.beacons:
56  tf.header.frame_id = b.frame_id
57  tf.child_frame_id = b.eid
58 
59  tf.transform.translation.x = b.position[0]
60  tf.transform.translation.y = b.position[1]
61  tf.transform.translation.z = b.position[2]
62 
63  tf.transform.rotation.x = 0
64  tf.transform.rotation.y = 0
65  tf.transform.rotation.z = 0
66  tf.transform.rotation.w = 1
67 
68  self.br.sendTransform(tf)
69  rospy.sleep(0.5)
70  # wait for next iteration
71  self.rate.sleep()
72 
73 
74 if __name__ == '__main__':
75  # start node
76  rospy.init_node('ips_map', anonymous=True)
77  # initialize IPSReceiver class
78  ips = IPSMap()
79  try:
80  # publish receiver messages
81  ips.publish()
82  except rospy.ROSInterruptException:
83  pass
def publish(self)
Definition: ips_map.py:49
def __init__(self)
Definition: ips_map.py:30


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