| 
					
	
	 
		Hi,
 
				I'm trying to get a pointcloud using rtabmap. To do this, I am subscribing to the rtabmap/cloud_map topic. However, while I do receive the sensor_msgs/PointCloud2 messages periodically in my node, these messages only report empty point clouds. When inspecting the topic with rostopic echo, I see that the height is 1 and width is 0, and the data array is empty. The rtabmap/mapData topic does report the correct data, albeit not in a PointCloud. When I use rtabmapviz, I can see the visualization of the point cloud. Also when using rviz I can see the point cloud (using the MapCloud visualization). Example of one cloud_map message: ---
header: 
  seq: 1254
  stamp: 
    secs: 3842
    nsecs: 530000000
  frame_id: "map"
height: 1
width: 0
fields: 
  - 
    name: "x"
    offset: 0
    datatype: 7
    count: 1
  - 
    name: "y"
    offset: 4
    datatype: 7
    count: 1
  - 
    name: "z"
    offset: 8
    datatype: 7
    count: 1
  - 
    name: "rgb"
    offset: 16
    datatype: 7
    count: 1
is_bigendian: False
point_step: 32
row_step: 0
data: []
is_dense: True
---My rqt_graph and screenshot of rtabmapviz can be found here. Any idea what I could be missing here? Do I need to set a parameter to enable the generation of the pointcloud using the mapData?  | 
			
| 
					
	 Administrator 
	
	
	
				 | 
				
					
	
	 
		Which rtabmap version do you have?
 
				Not sure about the scale of the point cloud, but cloud_map uses "Grid/" parameters to filter the cloud by range: $ rtabmap --params | grep Grid/Grid/DepthMax (or now Grid/RangeMax) can be set to 0 to avoid filtering the cloud. cheers, Mathieu  | 
			
| 
					
	
	 
		Hi Mathieu,
 
				I have the latest version installed through apt-get on Ubuntu, using ROS Kinetic. I think this is version 0.11.13? I don't think the scale is the cause of the problem. Even when flying very close to the building, the cloud_map is still empty. Also, when setting Grid/RangeMax to 0, the problem persists. It might maybe be useful to share the parameters that I'm using: 
    <param name="rgb/image_transport"   type="string" value="compressed"/>
    <param name="depth/image_transport" type="string" value="raw"/>
    <!-- RTAB-Map's parameters: do "rosrun rtabmap rtabmap (double-dash)params" to see the list of available parameters. -->
    <!--param name="RGBD/NeighborLinkRefining" type="string" value="true"/-->  <!-- Do odometry correction with consecutive laser scans -->
    <param name="RGBD/ProximityBySpace"     type="string" value="true"/>  <!-- Local loop closure detection (using estimated position) with locations in WM -->
    <param name="RGBD/ProximityByTime"      type="string" value="false"/> <!-- Local loop closure detection with locations in STM -->
    <param name="Reg/Strategy"              type="string" value="1"/>     <!-- 0=Visual, 1=ICP, 2=Visual+ICP -->
    <param name="Vis/InlierDistance"        type="string" value="0.1"/>   <!-- 3D visual words correspondence distance -->
    <param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/> <!-- Optimize graph from initial node so /map -> /odom transform will be generated -->
    <param name="Reg/Force3DoF"             type="string" value="true"/>
    <param name="Grid/FromDepth"            type="string" value="false"/>
    <param name="Grid/DepthMax"             type="double" value="0"/>
    <param name="subscribe_depth" type="bool" value="true"/>
    <param name="subscribe_scan"  type="bool" value="false"/>
	
	
	
	 | 
			
| 
					
	 Administrator 
	
	
	
				 | 
				
					
	
	 
		Set Grid/FromDepth to true. You may want to set Reg/Force3DoF to false if you do 6DoF trajectories.
	
	
	
	 
				 | 
			
| Free forum by Nabble | Edit this page | 
	
	
		