column_publisher.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 import yaml
5 import tf
6 import copy
7 
8 from geometry_msgs.msg import *
9 from rospy_message_converter import message_converter
10 from visualization_msgs.msg import *
11 from yocs_msgs.msg import *
12 
13 def publish(filename):
14  yaml_data = None
15  with open(filename) as f:
16  yaml_data = yaml.load(f)
17 
18  column_list = ColumnList()
19  # Markers
20  marker_list = MarkerArray()
21 
22  marker_id = 1
23  for t in yaml_data:
24  object = Column()
25  object.name = t['name']
26  object.radius = float(t['radius'])
27  object.height = float(t['height'])
28  object.pose.header.frame_id = t['frame_id']
29  object.pose.header.stamp = rospy.Time.now()
30  object.pose.pose.pose = message_converter.convert_dictionary_to_ros_message('geometry_msgs/Pose',t['pose'])
31  column_list.obstacles.append(object)
32 
33  marker = Marker()
34  marker.id = marker_id
35  marker.header = object.pose.header
36  marker.type = Marker.CYLINDER
37  marker.ns = "column_obstacles"
38  marker.action = Marker.ADD
39  marker.lifetime = rospy.Duration.from_sec(0)
40  marker.pose = copy.deepcopy(object.pose.pose.pose)
41  marker.pose.position.z += object.height/2.0
42  marker.scale.x = object.radius * 2
43  marker.scale.y = object.radius * 2
44  marker.scale.z = object.height
45  marker.color.r = 0
46  marker.color.g = 0
47  marker.color.b = 1.0
48  marker.color.a = 0.5
49 
50  marker_list.markers.append(marker)
51 
52  marker_id = marker_id + 1
53 
54  column_pub.publish(column_list)
55  marker_pub.publish(marker_list)
56 
57  return
58 
59 if __name__ == '__main__':
60  rospy.init_node('column_loader')
61  filename = rospy.get_param('~filename')
62 
63  marker_pub = rospy.Publisher('column_marker', MarkerArray, latch = True, queue_size=1)
64  column_pub = rospy.Publisher('column_pose_list', ColumnList, latch = True)
65 
66  rospy.loginfo('Publishing obstacles and visualization markers.')
67  publish(filename)
68  rospy.spin()
def publish(filename)


yocs_virtual_sensor
Author(s): Jorge Santos
autogenerated on Mon Jun 10 2019 15:54:08