ROS 包中 gmapping 模塊的參數翻譯

參照這個關於kinect v2轉爲laser傳感器建圖的帖子閱讀效果更佳。可以按照自己需求去改。

這個工程我覺得最大的問題在迴環檢測很弱,當然,單線激光雷達可能也就這個樣子了。

末尾附上我自己隨便改的參數,針對kinect2,可以反應的稍微快一點。

這個就是ROS 包中 gmapping 模塊的參數。

主要是意譯,能看懂就好。

Parameters

~inverted_laser (string, default: "false")
  • (REMOVED in 1.1.1; transform data is used instead) Is the laser right side up (scans are ordered CCW), or upside down (scans are ordered CW)?
  • 被刪了……
~throttle_scans (int, default: 1)
  • Process 1 out of every this many scans (set it to a higher number to skip more scans)
  • 從多少幀數據中取1幀,越高跳過的越多。(不確定是否是均值輸出)
~base_frame (string, default: "base_link")
  • The frame attached to the mobile base.
  • 與移動平臺關聯的框架。
~map_frame (string, default: "map")
  • The frame attached to the map.
  •  與地圖關聯的框架。
~odom_frame (string, default: "odom")
  • The frame attached to the odometry system.
  • 與里程儀系統關聯的框架。
~map_update_interval (float, default: 5.0)
  • How long (in seconds) between updates to the map. Lowering this number updates the occupancy grid more often, at the expense of greater computational load.
  • 佔據柵格地圖的更新頻率,默認5秒更新一次,調大提高系統負擔。(太慢了吧,不確定是否後臺更新還是所見即所得的更新。)
~maxUrange (float, default: 80.0)
  • The maximum usable range of the laser. A beam is cropped to this value.
  • 最大測量範圍,應該是米
~sigma (float, default: 0.05)
  • The sigma used by the greedy endpoint matching
  • 末端點匹配時的默認值。
~kernelSize (int, default: 1)
  • The kernel in which to look for a correspondence

尋找相關性的kernel大小

~lstep (float, default: 0.05)

  • The optimization step in translation
  • 平移的優化步長
~astep (float, default: 0.05)
  • The optimization step in rotation
  • 旋轉的優化步長
~iterations (int, default: 5)
  • The number of iterations of the scanmatcher
  • 迭代5次進行掃描結果的匹配(?)
~lsigma (float, default: 0.075)
  • The sigma of a beam used for likelihood computation
  • 近似計算一個光束的參數
~ogain (float, default: 3.0)
  • Gain to be used while evaluating the likelihood, for smoothing the resampling effects
  • 評估相似率的增益,用來平滑重採樣。
~lskip (int, default: 0)
  • Number of beams to skip in each scan. Take only every (n+1)th laser ray for computing a match (0 = take all rays)
  • 每次掃描中跳過的光束數量,也就是隔幾個光束採集一次,默認0就是全採。
~minimumScore (float, default: 0.0)
  • Minimum score for considering the outcome of the scan matching good. Can avoid jumping pose estimates in large open spaces when using laser scanners with limited range (e.g. 5m). Scores go up to 600+, try 50 for example when experiencing jumping estimate issues.
  • 這個有趣了,衡量掃描匹配效果的分數。當大場景中儀器的掃描範圍小的時候(5m)可以避免位姿估計跳動太大。最高可以設設成600以上。設成50看效果,應該是越大地圖越不會跳動。
~srr (float, default: 0.1)
  • Odometry error in translation as a function of translation (rho/rho)
  • 里程儀平移誤差,當作爲平移函數時(?)
~srt (float, default: 0.2)
  • Odometry error in translation as a function of rotation (rho/theta)
~str (float, default: 0.1)
  • Odometry error in rotation as a function of translation (theta/rho)
~stt (float, default: 0.2)
  • Odometry error in rotation as a function of rotation (theta/theta)
~linearUpdate (float, default: 1.0)
  • Process a scan each time the robot translates this far
  • 每當機器人平移這麼遠才掃描一次。小場景的話應該改小一點。
~angularUpdate (float, default: 0.5)
  • Process a scan each time the robot rotates this far
  • 每當機器人旋轉這麼多才掃描一次。小場景的話應該改小一點。
~temporalUpdate (float, default: -1.0)
  • Process a scan if the last scan processed is older than the update time in seconds. A value less than zero will turn time based updates off.
  • 當最後一次更新是x秒以前就自動更新一次。小於0就是關閉時間上的自動更新。
  • 這三句加起來就是應該分別設置更新掃描結果的依據,前兩個是運動,最後是時間。
~resampleThreshold (float, default: 0.5)
  • The Neff based resampling threshold
  • 基於Neff重採樣閾值。
~particles (int, default: 30)
  • Number of particles in the filter
  • 濾波器中的粒子數。(?)
~xmin (float, default: -100.0)
  • Initial map size (in metres)
  • 初始地圖X最小值
~ymin (float, default: -100.0)
  • Initial map size (in metres)
  • Y最小值
~xmax (float, default: 100.0)
  • Initial map size (in metres)
  • X最大值
~ymax (float, default: 100.0)
  • Initial map size (in metres)
  • Y最大值
~delta (float, default: 0.05)
  • Resolution of the map (in metres per occupancy grid block)
  • 地圖分辨率(每多少米一個佔據柵格)
~llsamplerange (float, default: 0.01)
  • Translational sampling range for the likelihood
  • 近似用的平移採樣範圍(?)
~llsamplestep (float, default: 0.01)
  • Translational sampling step for the likelihood
  • 近似用的平移採樣步長
~lasamplerange (float, default: 0.005)
  • Angular sampling range for the likelihood
  • 近似用的角度採樣範圍
~lasamplestep (float, default: 0.005)
  • Angular sampling step for the likelihood
  • 近似用的角度採樣步長
~transform_publish_period (float, default: 0.05)
  • How long (in seconds) between transform publications.
  • 發佈轉換(可能是位姿的)間隔多少秒
~occ_thresh (float, default: 0.25)
  • Threshold on gmapping's occupancy values. Cells with greater occupancy are considered occupied (i.e., set to 100 in the resulting sensor_msgs/LaserScan). New in 1.1.0.
  • gmapping 的佔據閾值。比這個大的單元就認爲被佔據了。(?)

~maxRange (float)

The maximum range of the sensor. If regions with no obstacles within the range of the sensor should appear as free space in the map, set maxUrange < maximum range of the real sensor <= maxRange.

傳感器最大範圍。要是想把傳感器範圍內沒有障礙的空間全設置成自由空間,那就設置成:maxUrange <真實傳感器的最大範圍<= maxRange.

一般來說是隻畫到遇到障礙爲止的區域認爲是自由空間,也可以激進的設成只要沒障礙就算自由空間。太激進了,不建議。

我自己測試的:kinect2_gmapping.launch

對比原版知道改哪裏更有用就好。

<?xml version="1.0"?>

<launch>    
    <!-- start kinect2-->            
    <include file="$(find kinect2_bridge)/launch/kinect2_bridge.launch">
        <arg name="base_name"         value="kinect2"/>
        <arg name="sensor"            value=""/>
        <arg name="publish_tf"        value="true"/>
        <arg name="base_name_tf"      value="kinect2"/>
        <arg name="fps_limit"         value="-1.0"/>
        <arg name="calib_path"        value="$(find kinect2_bridge)/data/"/>
        <arg name="use_png"           value="false"/>
        <arg name="jpeg_quality"      value="90"/>
        <arg name="png_level"         value="1"/>
        <arg name="depth_method"      value="default"/>
        <arg name="depth_device"      value="-1"/>
        <arg name="reg_method"        value="default"/>
        <arg name="reg_device"        value="-1"/>
        <arg name="max_depth"         value="12.0"/>
        <arg name="min_depth"         value="0.1"/>
        <arg name="queue_size"        value="5"/>
        <arg name="bilateral_filter"  value="true"/>
        <arg name="edge_aware_filter" value="true"/>
        <arg name="worker_threads"    value="4"/>
    </include>  

  <!-- Run the depthimage_to_laserscan node -->
  <node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan" output="screen">
    <!--輸入圖像-->
    <remap from="image" to="/kinect2/qhd/image_depth_rect"/>
    <!--相關圖像的相機信息。通常不需要重新變形,因爲camera_info將從與圖像相同的命名空間訂閱。-->
    <remap from="camera_info" to="/kinect2/qhd/camera_info" />
    <!--輸出激光數據的話題-->
    <remap from="scan" to="/scan" /> 

        <!--激光掃描的幀id。對於來自具有Z向前的“光學”幀的點雲,該值應該被設置爲具有X向前和Z向上的相應幀。-->
    <param name="output_frame_id" value="/kinect2_depth_frame"/>
    <!--用於生成激光掃描的像素行數。對於每一列,掃描將返回在圖像中垂直居中的那些像素的最小值。-->
    <param name="scan_height" value="30"/>
    <!--返回的最小範圍(以米爲單位)。小於該範圍的輸出將作爲-Inf輸出。-->
    <param name="range_min" value="0.01"/>
    <!--返回的最大範圍(以米爲單位)。大於此範圍將輸出爲+ Inf。-->
    <param name="range_max" value="8.00"/>
  </node>

    <!--start gmapping node -->
    <node pkg="gmapping" type="slam_gmapping" name="simple_gmapping" output="screen">
        <param name="map_update_interval" value="0.5"/>  
        <param name="maxUrange" value="5.0"/> 
        <param name="maxRange" value="8.0"/> 
        <param name="sigma" value="0.05"/>  
        <param name="kernelSize" value="1"/>  
        <param name="lstep" value="0.05"/>  
        <param name="astep" value="0.05"/>  
        <param name="iterations" value="5"/>  
        <param name="lsigma" value="0.075"/>  
        <param name="ogain" value="3.0"/>  
        <param name="lskip" value="0"/>  
        <param name="minimumScore" value="50"/>  
        <param name="srr" value="0.1"/>  
        <param name="srt" value="0.2"/>  
        <param name="str" value="0.1"/>  
        <param name="stt" value="0.2"/>  
        <param name="linearUpdate" value="0.2"/>  
        <param name="angularUpdate" value="0.2"/>  
        <param name="temporalUpdate" value="0.2"/>  
        <param name="resampleThreshold" value="0.5"/>  
        <param name="particles" value="50"/>  
        <param name="xmin" value="-5.0"/>  
        <param name="ymin" value="-5.0"/>  
        <param name="xmax" value="5.0"/>  
        <param name="ymax" value="5.0"/>  
        <param name="delta" value="0.05"/>  
        <param name="llsamplerange" value="0.01"/>  
        <param name="llsamplestep" value="0.01"/>  
        <param name="lasamplerange" value="0.005"/>  
        <param name="lasamplestep" value="0.005"/>  
        <param name="occ_thresh" value="0.01"/>  
    </node>

    <!--start serial-port and odometry node-->
    <node name="base_controller" pkg="base_controller" type="base_controller"/>

    <!-- static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period_in_ms -->  
  <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_base_link" args="0 0 0.5 0 0 0 base_footprint base_link 50" />
  <node pkg="tf" type="static_transform_publisher" name="base_link_to_laser" args="0 0 0.5 0 0 0 base_link laser 50" />
  <node pkg="tf" type="static_transform_publisher" name="base_link_to_kinect2laser" args="0 0 0.5 0 0 0 base_link kinect2_depth_frame 50" />
  <node pkg="tf" type="static_transform_publisher" name="base_link_to_kinect2_link" args="0 0 0.5 -1.57 0 -1.57 base_link kinect2_link 50" />
  <!--<node pkg="tf" type="static_transform_publisher" name="map_to_odom" args="0 0 0.5 0 0 0 map odom 50"/>-->
  <node pkg="tf" type="static_transform_publisher" name="odom_to_base_footprint" args="0 0 0.5 0 0 0 odom base_footprint 50"/>

</launch>

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章