Hi, I have used the outdoor mapping launch file with some modification from using GFTT+BRIEF
however no matter what i change I still get low features detected and poor mapping detection. Almost all the time i would lost tracking. I am using ROS Hydro with Rtabmap 0.7 <launch> <!-- Rotate the camera frame. --> <arg name="pi/2" value="1.5707963267948966" /> <arg name="camdist" value ="0.1397" /> <!--<arg name="optical_rotate" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)" />--> <arg name="optical_rotate" value="0.28 0.06 0.96 -1.55 0 -1.85" /> <node pkg="tf" type="static_transform_publisher" name="camera_base_link" args="$(arg optical_rotate) base_link stereo_camera 100" /> <!-- Run the ROS package stereo_image_proc --> <group ns="/stereo_camera" > <!-- Odometry --> <node pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen"> <remap from="left/image_rect" to="left/image_rect"/> <remap from="right/image_rect" to="right/image_rect"/> <remap from="left/camera_info" to="left/camera_info"/> <remap from="right/camera_info" to="right/camera_info"/> <remap from="odom" to="/stereo_camera/odom"/> <!-- addd --> <param name="frame_id" type="string" value="base_link"/> <param name="odom_frame_id" type="string" value="odom"/> <param name="approx_sync" type="bool" value="false"/> <param name="queue_size" type="int" value="30"/> <param name="Odom/InlierDistance" type="string" value="0.1"/> <param name="Odom/MinInliers" type="string" value="10"/> <param name="Odom/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/> <param name="Odom/MaxDepth" type="string" value="10"/> <param name="OdomBow/NNDR" type="string" value="0.8"/> <!--addd --> <param name="Odom/FillInfoData" type="string" value="true"/> <!-- - addd --> <param name="GFTT/MaxCorners" type="string" value="500"/> <param name="GFTT/MinDistance" type="string" value="5"/> </node> </group> <group ns="rtabmap"> <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start"> <param name="frame_id" type="string" value="base_link"/> <param name="subscribe_stereo" type="bool" value="true"/> <param name="subscribe_depth" type="bool" value="true"/> <param name="wait_for_transform" type="bool" value="true"/> <!--added--> <remap from="left/image_rect" to="/stereo_camera/left/image_rect_color"/> <remap from="right/image_rect" to="/stereo_camera/right/image_rect"/> <remap from="left/camera_info" to="/stereo_camera/left/camera_info"/> <remap from="right/camera_info" to="/stereo_camera/right/camera_info"/> <remap from="odom" to="/stereo_camera/odom"/> <param name="queue_size" type="int" value="30"/> <!-- RTAB-Map's parameters --> <param name="Rtabmap/TimeThr" type="string" value="0"/> <!--700--> <param name="Rtabmap/DetectionRate" type="string" value="1"/> <!--0--> <param name="Kp/WordsPerImage" type="string" value="0"/> <!-- 100 --> <param name="Kp/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/> <param name="Kp/DetectorStrategy" type="string" value="6"/> <!-- 0use SURF --> <param name="Kp/NNStrategy" type="string" value="3"/> <!-- 1kdTree --> <param name="SURF/HessianThreshold" type="string" value="1000"/> <param name="LccBow/MaxDepth" type="string" value="3"/> <!-- 10 --> <param name="LccBow/MinInliers" type="string" value="10"/> <param name="LccBow/InlierDistance" type="string" value="0.02"/> <!--0.1--> <param name="LccBow/EstimationType" type="string" value="1"/> <param name="LccReextract/Activated" type="string" value="true"/> <param name="LccReextract/MaxWords" type="string" value="0"/> <!-- 500 --> <param name="GFTT/MinDistance" type="string" value="1"/> <!-- ADDDED--> <param name="BRIEF/Bytes" type="string" value="32"/> <!-- ADDDED--> <param name="DbSqlite3/InMemory" type="string" value="true"/> <!-- ADDDED--> <param name="Mem/NotLinkedNodesKept" type="string" value="false"/> <!-- ADDDED--> <param name="Kp/MaxDepth" type="string" value="3"/> <!-- ADDDED--> <param name="RGBD/OptimizeFromGraphEnd" type="string" value="true"/> <!-- ADDDED--> <param name="RGBD/OptimizedIterations" type="string" value="10"/> <!--10 for GTSAM, 100 for TORO--> <param name="RGBD/OptimizeStrategy" type="string" value="0"/> <!--TOTO=0 g2o=1, GTSAM=2 2--> <param name="RGBD/OptimizeRobust" type="string" value="true"/> <param name="RGBD/LocalLoopDetectionSpace" type="string" value="true"/> <!-- Local loop closure detection (using estimated position) with locations in WM --> <param name="RGBD/LocalLoopDetectionTime" type="string" value="false"/> <!-- Local loop closure detection with locations in STM --> </node> <!-- Visualisation RTAB-Map --> <node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen"> <param name="subscribe_stereo" type="bool" value="true"/> <param name="subscribe_odom_info" type="bool" value="true"/> <param name="queue_size" type="int" value="10"/> <param name="frame_id" type="string" value="base_link"/> <remap from="left/image_rect" to="/stereo_camera/left/image_rect_color"/> <remap from="right/image_rect" to="/stereo_camera/right/image_rect"/> <remap from="left/camera_info" to="/stereo_camera/left/camera_info"/> <remap from="right/camera_info" to="/stereo_camera/right/camera_info"/> <remap from="odom_info" to="/stereo_camera/odom_info"/> <remap from="odom" to="/stereo_camera/odom"/> <remap from="mapData" to="mapData"/><!-- addd --> </node> </group> <node pkg="rviz" type="rviz" name="rviz" args="-d $(find rtabmap_ros)/launch/config/stereo_rviz.rviz"/> <!-- addd --> </launch> Initially i used the unmodified version but still low detection rate. <launch> <!-- Rotate the camera frame. --> <arg name="pi/2" value="1.5707963267948966" /> <arg name="camdist" value ="0.1397" /> <!--<arg name="optical_rotate" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)" />--> <arg name="optical_rotate" value="0.28 0.06 0.96 -1.55 0 -1.8" /> <node pkg="tf" type="static_transform_publisher" name="camera_base_link" args="$(arg optical_rotate) base_link stereo_camera 100" /> <!-- Run the ROS package stereo_image_proc --> <group ns="/stereo_camera" > <!-- Odometry --> <node pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen"> <remap from="left/image_rect" to="left/image_rect"/> <remap from="right/image_rect" to="right/image_rect"/> <remap from="left/camera_info" to="left/camera_info"/> <remap from="right/camera_info" to="right/camera_info"/> <remap from="odom" to="/stereo_camera/odom"/> <!-- addd --> <param name="frame_id" type="string" value="base_link"/> <param name="odom_frame_id" type="string" value="odom"/> <param name="approx_sync" type="bool" value="false"/> <param name="queue_size" type="int" value="30"/> <param name="Odom/InlierDistance" type="string" value="0.1"/> <param name="Odom/MinInliers" type="string" value="10"/> <param name="Odom/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/> <param name="Odom/MaxDepth" type="string" value="10"/> <param name="OdomBow/NNDR" type="string" value="0.8"/> <!--addd --> <param name="Odom/FillInfoData" type="string" value="true"/> <!-- - addd --> <param name="GFTT/MaxCorners" type="string" value="500"/> <param name="GFTT/MinDistance" type="string" value="5"/> </node> </group> <group ns="rtabmap"> <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start"> <param name="frame_id" type="string" value="base_link"/> <param name="subscribe_stereo" type="bool" value="true"/> <param name="subscribe_depth" type="bool" value="true"/> <param name="wait_for_transform" type="bool" value="true"/> <!--added--> <remap from="left/image_rect" to="/stereo_camera/left/image_rect_color"/> <remap from="right/image_rect" to="/stereo_camera/right/image_rect"/> <remap from="left/camera_info" to="/stereo_camera/left/camera_info"/> <remap from="right/camera_info" to="/stereo_camera/right/camera_info"/> <remap from="odom" to="/stereo_camera/odom"/> <param name="queue_size" type="int" value="30"/> <!-- RTAB-Map's parameters --> <param name="Rtabmap/TimeThr" type="string" value="700"/> <!--700--> <param name="Rtabmap/DetectionRate" type="string" value="0"/> <!--0--> <param name="Kp/WordsPerImage" type="string" value="100"/> <!-- 100 --> <param name="Kp/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/> <param name="Kp/DetectorStrategy" type="string" value="0"/> <!-- 0use SURF --> <param name="Kp/NNStrategy" type="string" value="1"/> <!-- 1kdTree --> <param name="SURF/HessianThreshold" type="string" value="1000"/> <param name="LccBow/MaxDepth" type="string" value="10"/> <!-- 10 --> <param name="LccBow/MinInliers" type="string" value="10"/> <param name="LccBow/InlierDistance" type="string" value="0.1"/> <!--0.1--> <param name="LccBow/EstimationType" type="string" value="1"/> <param name="LccReextract/Activated" type="string" value="true"/> <param name="LccReextract/MaxWords" type="string" value="500"/> <!-- 500 --> <param name="RGBD/OptimizedIterations" type="string" value="10"/> <!--10 for GTSAM, 100 for TORO--> <param name="RGBD/OptimizeStrategy" type="string" value="2"/> <!--TOTO=0 g2o=1, GTSAM=2 2--> <param name="RGBD/OptimizeRobust" type="string" value="true"/> <param name="RGBD/LocalLoopDetectionSpace" type="string" value="true"/> <!-- Local loop closure detection (using estimated position) with locations in WM --> <param name="RGBD/LocalLoopDetectionTime" type="string" value="false"/> <!-- Local loop closure detection with locations in STM --> </node> <!-- Visualisation RTAB-Map --> <node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen"> <param name="subscribe_stereo" type="bool" value="true"/> <param name="subscribe_odom_info" type="bool" value="true"/> <param name="queue_size" type="int" value="10"/> <param name="frame_id" type="string" value="base_link"/> <remap from="left/image_rect" to="/stereo_camera/left/image_rect_color"/> <remap from="right/image_rect" to="/stereo_camera/right/image_rect"/> <remap from="left/camera_info" to="/stereo_camera/left/camera_info"/> <remap from="right/camera_info" to="/stereo_camera/right/camera_info"/> <remap from="odom_info" to="/stereo_camera/odom_info"/> <remap from="odom" to="/stereo_camera/odom"/> <remap from="mapData" to="mapData"/><!-- addd --> </node> </group> <node pkg="rviz" type="rviz" name="rviz" args="-d $(find rtabmap_ros)/launch/config/stereo_rviz.rviz"/> <!-- addd --> </launch> I am using a PGR Bumblebee2 BB2 and have calibrated the stereo camera. I have mounted the camera in such a way below Could it be the Stereo Camera? Here is some of the failure to detect It is quite hard to get features detected I am not sure why it is so. Thanks |
Administrator
|
Hi,
I recommend to use the latest version of rtabmap from GitHub master branch. It should build on Hydro. See Build from source section. You've made a lot of changes under rtabmap node. These changes will only affect the loop closure detection performance. I prefer to use SIFT/SURF/ORB (rotation invariant) features for loop closure detection. In your case, it seems to be an odometry tracking problem, so tuning parameters should be done under stereo_odometry node. Some examples to try: <!-- Odometry --> <node pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen"> <param name="GFTT/MaxCorners" type="string" value="1000"/> <!-- more features to track, you can even set to 0 (not bounded) but odometry will be computed less fast --> <param name="GFTT/QualityLevel" type="string" value="0.0001"/> <!-- with low quality level, more features will be extracted in dark areas --> <param name="Odom/EstimationType" type="string" value="1"/> <!-- use PnP transform estimation --> <param name="Odom/PnPReprojError" type="string" value="2"/> <!-- (pixels) for PnP --> ... </node> For convenience, you can show all odometry parameters using: $ rosrun rtabmap_ros stereo_odometry --params cheers, Mathieu |
In reply to this post by chainer
So i just rebuild with the source? Cus i aready installed using sudo apt-get install ros-hydro-rtabmap-ros
do i need to remove it first or just follow the Build from source instruction? |
Administrator
|
Hi,
Yes, uninstall ros-hydro-rtabmap and ros-hydro-rtabmap-ros: $ sudo apt-get remove ros-hydro-rtabmap ros-hydro-rtabmap-rosthen follow instructions from point 2 (you can skip the optional dependencies section in your case as they should be already installed). cheers |
Free forum by Nabble | Edit this page |