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
    20 assembledCloud = PointCloud2()
    21 pub = rospy.Publisher(
'assembled_local_grids', PointCloud2, queue_size=10)
    29     begin = rospy.get_time()
    31     nodeId = graph.posesId[-1]
    32     pose = graph.poses[-1]
    35     posesDict[nodeId] = pose
    36     cloudsDict[nodeId] = cloud
    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)])
    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()
    54     newGraph = Set(graph.posesId)
    56     for p 
in posesDict.keys():
    61             totalPoints = totalPoints + cloudsDict[p].width
    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]
    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)
    75                 newAssembledCloud = transformedCloud
    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
    83         t.transform.translation = pose.position
    84         t.transform.rotation = pose.orientation
    85         transformedCloud = do_transform_cloud(cloud, t)
    87         if assembledCloud.width == 0:
    88             assembledCloud = transformedCloud
    91             assembledCloud.data = assembledCloud.data + transformedCloud.data
    92             assembledCloud.width = assembledCloud.width + transformedCloud.width
    93             assembledCloud.row_step = assembledCloud.row_step + transformedCloud.row_step
    95     updateTime = rospy.get_time() - begin
    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)", 
    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)
   103     assembledCloud.header = graph.header
   104     pub.publish(assembledCloud)
   107     rospy.init_node(
'assemble_local_grids', anonymous=
True)
   112     ts.registerCallback(callback)
   115 if __name__ == 
'__main__':
   118     except rospy.ROSInterruptException:
 
def callback(graph, cloud)
GLM_FUNC_DECL genType abs(genType const &x)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)