rtabmap_ros icon indicating copy to clipboard operation
rtabmap_ros copied to clipboard

superpoint with no gpu

Open fbliman opened this issue 1 year ago • 1 comments

Hi, I am trying to use superpoint with no gpu. I know that I can not use superglue, with feature matching should I use.

and also I am getting this error:

[ WARN] (2023-07-04 19:49:21.726) Memory.cpp:798::parseParameters() Mem/UseOdomFeatures is enabled, but Vis/FeatureType and Kp/DetectorStrategy parameters are not the same! Disabling Mem/UseOdomFeatures...

I set both parameters to 11(Superpoint) what can it be wrong

my launch file : `

  <node if="$(arg stereo_sync)" pkg="nodelet" type="nodelet" name="stereo_sync" args="standalone rtabmap_ros/stereo_sync">
  <remap from="left/image_rect"   to="left/image_rect_color"/>
  <remap from="right/image_rect"   to="right/image_rect"/>
  <remap from="left/camera_info"   to="left/camera_info_throttle"/>
  <remap from="right/camera_info"   to="right/camera_info_throttle"/>
</node>
  <!-- Stereo Odometry -->   
  <node pkg="rtabmap_odom" type="stereo_odometry" name="stereo_odometry" output="screen" >
     <remap from="left/image_rect"       to="/stereo_camera/left/image_rect"/>
     <remap from="right/image_rect"      to="/stereo_camera/right/image_rect"/>
     <remap from="left/camera_info"      to="/zed_front/zed_node_front/left/camera_info"/>
     <remap from="right/camera_info"     to="/zed_front/zed_node_front/right/camera_info"/>
     <remap from="rgbd_image"            to="/stereo_camera/rgbd_image"/>
     <remap from="odom"                  to="/stereo_odometry"/>
     <remap from="imu"                  to="/imu/data"/>

     <param name="subscribe_rgbd"  type="bool" value="$(arg stereo_sync)"/>
     <param name="frame_id"        type="string" value="base_link"/>
     <param name="odom_frame_id"   type="string" value="odom"/>

     <param name="Odom/Strategy" type="string" value="0"/> <!-- 0=BOW, 1=OpticalFlow -->
     <param name="Vis/CorType" value="0"/>  <!-- Correspondences: 0=Features Matching, 1=Optical Flow -->

     <param name="Vis/EstimationType" type="string" value="1"/> <!-- 3D->2D (PnP) -->
     <param name="Vis/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/>
     <param name="Vis/MaxDepth"       type="string" value="0"/>
     <param name="Odom/GuessMotion" type="string" value="true"/>
     <param name="Vis/MinInliers"     type="string" value="10"/>
     <param name="Vis/NNDR" type="string" value="0.8"/>
     <param name="Vis/MaxFeatures" type="string" value="1000"/>
     <param name="Odom/FillInfoData" type="string" value="$(arg rtabmap_viz)"/>
     <param name="GFTT/MinDistance" type="string" value="10"/>
     <param name="GFTT/QualityLevel" type="string" value="0.00001"/> 
     <param name="Vis/FeatureType=11" type="string" value="11"/>
     <param name="Kp/DetectorStrategy"  type="string" value="11"/>  
     

     <!-- nuevo -->
     <param name="Reg/Force3DoF"    value="true" />
     <param name="wait_imu_to_init"            type="bool"   value="true"/>
     <param name="imu_topic"            type="string"   value="/imu/data"/>

    
  </node>

   <!-- Visual SLAM: args: "delete_db_on_start" and "udebug"  -->
  <node name="rtabmap" pkg="rtabmap_slam" type="rtabmap" output="screen" args="--delete_db_on_start" >
     <param name="frame_id"         type="string" value="base_link"/>
     <param unless="$(arg stereo_sync)" name="subscribe_stereo" type="bool" value="true"/>
     <param name="subscribe_depth"  type="bool" value="false"/>
     <param name="subscribe_rgbd"      type="bool" value="$(arg stereo_sync)"/>

     <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="/zed_front/zed_node_front/left/camera_info"/>
     <remap from="right/camera_info" to="/zed_front/zed_node_front/right/camera_info"/>
     <remap from="rgbd_image"        to="/stereo_camera/rgbd_image"/>

     <remap from="odom" to="/stereo_odometry"/>

     <param name="queue_size" type="int" value="30"/>
     <!--param name="map_negative_poses_ignored" type="bool" value="true"/-->

     <!-- RTAB-Map's parameters -->
     <param name="Rtabmap/TimeThr"                   type="string" value="700"/>
     <param name="Grid/DepthDecimation"              type="string" value="4"/>
     <param name="Grid/FlatObstacleDetected"         type="string" value="true"/>
     <param name="Kp/MaxDepth"                       type="string" value="0"/>
     <param name="Kp/DetectorStrategy"               type="string" value="11"/> 
     <param name="Vis/FeatureType=11"                type="string" value="11"/>
     <param name="SuperPoint/ModelPath"              type="string" value="$(find rtabmap_ros)/superpoint.pt"/>
     <param name="Vis/CorNNType"                     type="string" value="3"/>
     <param name="Vis/EstimationType"                type="string" value="1"/>   <!-- 0=3D->3D, 1=3D->2D (PnP) -->
     <param name="Vis/MaxDepth"                      type="string" value="0"/>
     <param name="RGBD/CreateOccupancyGrid"          type="string" value="true"/>       
     <param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>       
     <param name="Rtabmap/StartNewMapOnLoopClosure" value="true"/>


      <!-- nuevo -->
     <param name="Reg/Force3DoF"    value="true" />
     <param name="Optimizer/Slam2D" value="true" />
    
  </node>

  <!-- Visualisation RTAB-Map -->
  <node if="$(arg rtabmap_viz)" pkg="rtabmap_viz" type="rtabmap_viz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
     <param unless="$(arg stereo_sync)" name="subscribe_stereo"    type="bool" value="true"/>
     <param name="subscribe_odom_info" type="bool" value="true"/>
     <param name="subscribe_rgbd"      type="bool" value="$(arg stereo_sync)"/>
     <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="/zed_front/zed_node_front/left/camera_info"/>
     <remap from="right/camera_info" to="/zed_front/zed_node_front/right/camera_info"/>
     <remap from="rgbd_image"          to="/stereo_camera/rgbd_image"/>
     <remap from="odom_info"         to="odom_info"/>
     <remap from="odom"              to="/stereo_odometry"/>
     <remap from="mapData"           to="mapData"/>
  </node>
     
`

fbliman avatar Jul 04 '23 22:07 fbliman

Default feature matching will wotrk with superpoint, you may decrease Vis/CorNNDR to 0.6 though.

There is a typo here:

<param name="Vis/FeatureType=11"                type="string" value="11"/>

<param name="Vis/FeatureType"                type="string" value="11"/>

matlabbe avatar Jul 07 '23 05:07 matlabbe