Hi Mathieu,
Finally I put everything to work, from Intel R200 with Rtabmap to local and global costmap and Teb local planner. I'm testing the Robot in the field (agricultural purpose) and I'm stuck looking for a valid option to set a min obstacle height for proj_map (input of global costmap). Since I have obstacles like grass or small pieces of tree branch I would like to filter them out as I already did with local costmap. In local costmap I have the min height parameter of point_cloud_sensor but no equal parameter on proj_map/global map. Do you have some suggestion about that? I would like to filter small objects out and keep ground visible. I'm not using fake laser scan. (I hear right know that proj_map and grid_map are deprecated on latest version, I'm using Ros Indigo). Thank you. Andrea |
Administrator
|
Hi Andrea,
What you are looking for is this just that all points below a fixed height are ground? If so, it is possible with latest version (source or Kinetic) with <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap"> <param name="Grid/MaxGroundHeight" type="string" value="0.2"/> <!-- all points below 20 cm are ground --> <param name="Grid/MaxObstacleHeight" type="string" value="2"/> <!-- all points above 20 cm and below 2 m are obstacles --> <param name="Grid/NormalsSegmentation" type="string" value="false"/> <!-- Use simple passthrough to filter the ground instead of normals segmentation --> </node> Indeed, in future /proj_map will be removed keeping only /grid_map. /grid_map depends now on "Grid/*" parameters. For example, depending on the value of "Grid/FromDepth", the /grid_map is created from laser scan if false or depth image like the old /proj_map if true. cheers, Mathieu |
Yes, exactly!
Thank you for the suggestion I'll try it ASAP. The new "architecture" seems more understandable and straightforward. I try to not break what I did until now compiling from source for Indigo. Andrea |
Hi Mathieu,
I successfully compiled the latest rtabmap from github on indigo: here the instruction I followed. Could be useful since there was some errors during compilation: source /opt/ros/indigo/setup.bash source ~/catkin_ws/devel/setup.bash $ sudo apt-get install ros-kinetic-rtabmap ros-kinetic-rtabmap-ros $ sudo apt-get remove ros-kinetic-rtabmap ros-kinetic-rtabmap-ros $ cd ~ $ git clone https://github.com/introlab/rtabmap.git rtabmap $ cd rtabmap/build $ cmake -DCMAKE_INSTALL_PREFIX=~/catkin_ws/devel .. [<---double dots included] $ sudo dpkg -r --force-depends "libopenni-dev" && sudo apt-get install libopenni-dev $ make -j2 $ sudo make install [Install RTAB-Map ros-pkg in your src folder of your Catkin workspace.] $ cd ~/catkin_ws $ git clone https://github.com/introlab/rtabmap_ros.git src/rtabmap_ros $ catkin_make -j1 Everything is fine and now I'm able to set the max ground height as expected. I found that is changed the ground cloud output topic of obstacles detection nodelet. The indigo compiled version was "ground" (and I mapped the output in this way " <remap from="ground" to="/ground_cloud"/> " but now no data coming out from /ground or /ground_cloud , only from the new topic "/rtabmap/cloud_ground" . Seems strange 'cause obstacle cloud is still there without any modification. Did you change the output topic name of ground cloud in obstacles detection nodelet? Thank you Andrea |
Administrator
|
Hi,
thx for the instructions, though libopenni-dev may not be required from a clean install. I added a note for "catkin_make -j1" usage (for computer with low RAM). The output of obstacles_detection nodelet should still be called "ground", see here, though now it uses the same "Grid/***" parameters than rtabmap node. Can you show rqt_viz (with all topics shown)? cheers, Mathieu |
Hi,
mmhhh, interesting. I attached the screenshot from rviz (gazebo sim not real robot) in which you can see on the right the correct red obstacle cloud (I set 0.7m from the ground to keep it clear and visible) but no ground cloud (should be in dark yellow over the costmaps). On the left the list of all available topics. No data if I select /ground. I have data only if I select /rtabmap/cloud_ground. By the way local costmap, global costmap and map is working fine so it's not a big issue (right now). |
Administrator
|
Hi,
Can you try this launch file (change camera topic and attached nodelets manager to obstacles_detection if required)? <launch> <!-- Camera --> <include file="$(find freenect_launch)/launch/freenect.launch"> <arg name="depth_registration" value="True" /> </include> <group ns="camera"> <!-- Run a VoxelGrid filter to clean NaNs and downsample the data --> <node pkg="nodelet" type="nodelet" name="voxel_grid" args="load pcl/VoxelGrid camera_nodelet_manager" output="screen"> <remap from="~input" to="/camera/depth_registered/points" /> <remap from="~output" to="/camera/depth_registered/points_downsampled" /> <rosparam> filter_field_name: z filter_limit_min: 0.01 filter_limit_max: 10 filter_limit_negative: False leaf_size: 0.01 </rosparam> </node> <node pkg="nodelet" type="nodelet" name="obstacles_detection" args="load rtabmap_ros/obstacles_detection camera_nodelet_manager" output="screen"> <remap from="cloud" to="/camera/depth_registered/points_downsampled"/> <param name="frame_id" type="string" value="camera_link"/> <param name="Grid/NormalsSegmentation" type="string" value="true"/> </node> </group> </launch> With "Grid/NormalsSegmentation=true" (ground plane segmented): With "Grid/NormalsSegmentation=false" (cloud cut at z=0): It seems working, maybe there is an other parameter that makes the ground cloud empty. cheers, Mathieu |
Hi,
finally I put it to work setting explicit: <param name="Grid/NormalsSegmentation" type="string" value="false"/> here the output from the regular /ground_cloud of obstacles_detection nodelet: thank you for your support! |
Free forum by Nabble | Edit this page |