assemble_local_grids.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Similar to map_assembler node, this minimal python example shows how
4 # to reconstruct the obstacle map by subscribing only to
5 # graph and latest data added to map (for constant network bandwidth usage).
6 
7 import rospy
8 from sets import Set
9 
10 import message_filters
11 from rtabmap_ros.msg import MapGraph
12 from sensor_msgs.msg import PointCloud2
13 from geometry_msgs.msg import Pose
14 from geometry_msgs.msg import TransformStamped
15 from tf2_sensor_msgs.tf2_sensor_msgs import do_transform_cloud
16 
17 
18 posesDict = {}
19 cloudsDict = {}
20 assembledCloud = PointCloud2()
21 pub = rospy.Publisher('assembled_local_grids', PointCloud2, queue_size=10)
22 
23 def callback(graph, cloud):
24  global assembledCloud
25  global posesDict
26  global cloudsDict
27  global pub
28 
29  begin = rospy.get_time()
30 
31  nodeId = graph.posesId[-1]
32  pose = graph.poses[-1]
33  size = cloud.width
34 
35  posesDict[nodeId] = pose
36  cloudsDict[nodeId] = cloud
37 
38  # Update pose of our buffered clouds.
39  # Check also if the clouds have moved because of a loop closure. If so, we have to update the rendering.
40  maxDiff = 0
41  for i in range(0,len(graph.posesId)):
42  if graph.posesId[i] in posesDict:
43  currentPose = posesDict[graph.posesId[i]].position
44  newPose = graph.poses[i].position
45  diff = max([abs(currentPose.x-newPose.x), abs(currentPose.y-newPose.y), abs(currentPose.z-newPose.z)])
46  if maxDiff < diff:
47  maxDiff = diff
48  else:
49  rospy.loginfo("Old node %d not found in cache, creating an empty cloud.", graph.posesId[i])
50  posesDict[graph.posesId[i]] = graph.poses[i]
51  cloudsDict[graph.posesId[i]] = PointCloud2()
52 
53  # If we don't move, some nodes would be removed from the graph, so remove them from our buffered clouds.
54  newGraph = Set(graph.posesId)
55  totalPoints = 0
56  for p in posesDict.keys():
57  if p not in newGraph:
58  posesDict.pop(p)
59  cloudsDict.pop(p)
60  else:
61  totalPoints = totalPoints + cloudsDict[p].width
62 
63  if maxDiff > 0.1:
64  # if any node moved more than 10 cm, request an update of the assembled map so far
65  newAssembledCloud = PointCloud2()
66  rospy.loginfo("Map has been optimized! maxDiff=%.3fm, re-updating the whole map...", maxDiff)
67  for i in range(0,len(graph.posesId)):
68  posesDict[graph.posesId[i]] = graph.poses[i]
69  t = TransformStamped()
70  p = posesDict[graph.posesId[i]]
71  t.transform.translation = p.position
72  t.transform.rotation = p.orientation
73  transformedCloud = do_transform_cloud(cloudsDict[graph.posesId[i]], t)
74  if i==0:
75  newAssembledCloud = transformedCloud
76  else:
77  newAssembledCloud.data = newAssembledCloud.data + transformedCloud.data
78  newAssembledCloud.width = newAssembledCloud.width + transformedCloud.width
79  newAssembledCloud.row_step = newAssembledCloud.row_step + transformedCloud.row_step
80  assembledCloud = newAssembledCloud
81  else:
82  t = TransformStamped()
83  t.transform.translation = pose.position
84  t.transform.rotation = pose.orientation
85  transformedCloud = do_transform_cloud(cloud, t)
86  # just concatenate new cloud to current assembled map
87  if assembledCloud.width == 0:
88  assembledCloud = transformedCloud
89  else:
90  # Adding only the difference would be more efficient
91  assembledCloud.data = assembledCloud.data + transformedCloud.data
92  assembledCloud.width = assembledCloud.width + transformedCloud.width
93  assembledCloud.row_step = assembledCloud.row_step + transformedCloud.row_step
94 
95  updateTime = rospy.get_time() - begin
96 
97  rospy.loginfo("Received node %d (%d pts) at xyz=%.2f %.2f %.2f, q_xyzw=%.2f %.2f %.2f %.2f (Map: Nodes=%d Points=%d Assembled=%d Update=%.0fms)",
98  nodeId, size,
99  pose.position.x, pose.position.y, pose.position.z,
100  pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w,
101  len(cloudsDict), totalPoints, assembledCloud.width, updateTime*1000)
102 
103  assembledCloud.header = graph.header
104  pub.publish(assembledCloud)
105 
106 def main():
107  rospy.init_node('assemble_local_grids', anonymous=True)
108  graph_sub = message_filters.Subscriber('rtabmap/mapGraph', MapGraph)
109  cloud_sub = message_filters.Subscriber('rtabmap/local_grid_obstacle', PointCloud2)
110 
111  ts = message_filters.TimeSynchronizer([graph_sub, cloud_sub], 2)
112  ts.registerCallback(callback)
113  rospy.spin()
114 
115 if __name__ == '__main__':
116  try:
117  main()
118  except rospy.ROSInterruptException:
119  pass
def callback(graph, cloud)
GLM_FUNC_DECL genType abs(genType const &x)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:18