Login  Register

Localization after mapping session using lidar only

Posted by Bracky on Dec 20, 2022; 9:50am
URL: http://official-rtab-map-forum.206.s1.nabble.com/Localization-after-mapping-session-using-lidar-only-tp9260.html

Hello Matthieu, Hello everyone,
So I am trying to localize in 2D my robot. The robot's task are 1) leave station 2) do stuff 3) return to station. Which is why when leave, I am trying to create a map in which I can localize in for returning to station. However, I only have a lidar.
Creating the map works but localizing in it does not.
 
One (or more) of my parameters might be incorrect in my launch file. Any ideas ?
<launch>       
<!-- Choose visualization -->
<arg name="rviz"    default="true" />

<arg name="use_imu" default="true" />
<arg name="imu_topic" default="truc/truc" />
<arg name="localization" value="true"/>

<arg     if="$(arg localization)" name="rtabmap_args"  default="localization:=true"/>
<arg unless="$(arg localization)" name="rtabmap_args"  default="--delete_db_on_start"/>
    
<!-- Point to Plane ICP? -->
<arg name="p2n" default="false" />
    
<group ns="rtabmap">
<node pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="screen" >
             <remap from="scan_cloud"      to="/lidar/points"/>
             <remap from="odom_info"      to="/rtabmap/odom_info"/>
            <param name="subscribe_scan"        type="bool"     value="false"/>
            <param name="subscribe_scan_cloud"  type="bool"     value="true"/>
            <param name="odom_frame_id"         type="string"   value="odom"/>
            <param name="frame_id"              type="string"   value="base_link"/>
            <param name="deskewing"             type="string"   value="true"/>
            <remap if="$(arg use_imu)" from="imu" to="$(arg imu_topic)"/>
            <param if="$(arg use_imu)" name="guess_frame_id"   type="string" value="base_link"/>
            <param if="$(arg use_imu)" name="wait_imu_to_init" type="bool" value="true"/>
            <param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
            <param if="$(arg localization)" name="Mem/InitWMWithAllNodes" type="string" value="true"/>
            <param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
            <param unless="$(arg localization)" name="Mem/InitWMWithAllNodes" type="string" value="false"/>                       
            <param name="Icp/MaxCorrespondenceDistance"     type="double"      value="10"/>
            <param name="Icp/Iterations"                    type="int"      value="100"/>
            <param name="Icp/Strategy"                      type="int"      value="1"/>
            <param name="Icp/VoxelSize"     type="string" value="0.05"/>
            <param name="Icp/RangeMax"      type="string" value="0"/>
            <param name="Icp/Epsilon"       type="string" value="0.001"/>
            <param name="Icp/MaxTranslation" type="string" value="3"/>
            <param if="$(arg p2n)" name="Icp/PointToPlane"  type="string" value="true"/>
            <param if="$(arg p2n)" name="Icp/PointToPlaneK"  type="string" value="5"/>
            <param if="$(arg p2n)" name="Icp/PointToPlaneRadius"  type="string" value="0.3"/>
            <param unless="$(arg p2n)" name="Icp/PointToPlane"  type="string" value="false"/>
            <param unless="$(arg p2n)" name="Icp/PointToPlaneK"  type="string" value="0"/>
            <param unless="$(arg p2n)" name="Icp/PointToPlaneRadius"  type="string" value="0"/>
            <param name="Icp/MaxCorrespondenceDistance" type="string" value="10"/>
            <param name="Odom/Strategy"        type="string" value="0"/>
            <param name="Odom/FilteringStrategy" type="int"  value="1"/>
            <param name="Odom/GuessMotion"     type="string" value="true"/><!-- can't guess transform from null transform-->
            <param name="Odom/ResetCountdown"  type="string" value="0"/>
            <param name="Odom/ScanKeyFrameThr"  type="string" value="0.9"/>
        </node>

        <node name="rtabmap" pkg="rtabmap_ros"  type="rtabmap"  output="screen" args="$(arg rtabmap_args)">
            <param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
            <param if="$(arg localization)" name="Mem/InitWMWithAllNodes" type="string" value="true"/>
            <param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
            <param unless="$(arg localization)" name="Mem/InitWMWithAllNodes" type="string" value="false"/>
            <!--topics related-->
            <param name="queue_size"            type="int"      value="10"/>
            <param if="$(arg localization)"     name="publish_tf"            type="bool" value="false"/>
            <param name="tf_delay"              type="double"   value="0.05"/>
            <param name="tf_prefix"             type="string"   value=""/>
            <param name="wait_for_transform"    type="bool"     value="true"/>
            <!-- devices -->
            <param name="subscribe_depth"       type="bool"     value="false"/>
            <param name="subscribe_rgb"         type="bool"     value="false"/>
            <param name="subscribe_scan"        type="bool"     value="false"/>
            <param name="subscribe_scan_cloud"  type="bool"     value="true"/>            
            <remap from="/gps/fix"          to="/rr100/navsat/fix"/>
            <remap from="scan_cloud"        to="/lidar/points"/>
            <!-- frames -->
            <param name="frame_id"              type="string"   value="base_footprint"/>
            <param name="map_frame_id"          type="string"   value="map"/>
            <param name="odom_frame_id"         type="string"   value="odom"/>
            <param name="publish_tf"            type="bool"     value="true"/>
            <param if=    "$(arg localization)"    name="database_path"         type="string"   value="~/.ros/rtabmap_clean.db"/>
            <param unless="$(arg localization)"    name="database_path"         type="string"   value="~/.ros/rtabmap.db"/>
            <!--mapping-->	
            <param name="map_cleanup"               type="bool"     value="false"/>
            <param name="map_always_update"         type="bool"     value="true"/>
            <param name="map_empty_ray_tracing"     type="bool"     value="true"/>            
            <param name="Rtabmap/DetectionRate"     type="double"   value="5"/>
            <param name="Rtabmap/LoopGPS"           type="bool"     value="false"/>
            <param name="Odom/Holonomic"            type="bool"     value="false"/>
            <param name="Odom/AlignWithGround"      type="bool"     value="true"/>
            <param name="Reg/Strategy"              type="int"      value="1"/><!--0=Vis, 1=Icp, 2=VisIcp-->
            <param name="Reg/Force3DoF"             type="bool"     value="true"/>
            <param name="Icp/Strategy"              type="int"      value="1"/>
            <param name="Icp/CorrespondenceRatio"   type="string"   value="0.2"/>
            <param name="Icp/VoxelSize"             type="string"   value="0.05"/>
            <param name="Icp/RangeMax"              type="string"   value="0"/>
            <param name="Grid/RangeMax"             type="string"   value="0"/>
            <param name="Grid/Sensor"               type="int"      value="0"/>
        </node>
    </group>
    <!-- Visualisation RVIZ -->
    <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(find rtabmap_ros)/launch/config/demo_robot_mapping.rviz" output="screen"/>
</launch>


To get this result I 1) launch my gazebo world, 2) move the robot and the node above in SLAM mode 3) stop the node above 4) move my robot 5) start the node above in localization mode.
I believe that loop closure is required for localization and it seems that there is no "bag of words" as I am using ICP, so a simple icp_odometry allowing high jump should do the job ?

Thanks in advance for your advices and your help ;)