ROS 中obstacle_layer由於激光雷達測距的侷限性,導致costmap中障礙物不能被及時清除。

使用navigation導航時,會出現由於激光雷達測距的侷限性, 會導致costmap,比如說 有行人走過,代價地圖中的障礙物,無法被及時的清除。這個問題,主要由於,激光雷達基於三角測距原理,當 測距的距離超過激光雷達的極限,導致無法測到距離,就沒有相對應的數據。 

根據不同的激光雷達,在測不到數據時, sick等比較貴的雷達,返回的是inf,無窮值。在32位的浮點型數據中,當數位都爲1時,表示數值無窮大。

符號位S:1位 階碼(指數位) :8位 尾數:————- 23 位


(尾數是原本的二進制數,因爲浮點計數,有點像科學計數法的x.xxxx*(10^y),頭一位一定是1,所以把1捨去了,比如 1.010101*(2^5),存起來就是:0 //5-127//0101010….00 )
而國內一些比較便宜的激光雷達,在未測到數據時,返回的是0.0 或者激光雷達默認的最大值。

實驗的現象主要如下所表現: 由於解決時,未保存圖,所以圖摘自ros論壇。


當有行人走過時,機器人的附近會留下一些之前的圖中藍色的障礙點,這將會影響後續的導航和壁障,而原因,前面已經描述了。這個問題幾乎是機器人只要在大環境下,都肯定會遇到。會比如下圖 紅色框圈出來的區域。這是由於人走過去留下的,實際中,沒有障礙物。


所以,怎麼解決呢;  就要修改navigation這個代碼包啦。

在catkin_ws的工作區間中,git clone https://github.com/ros-planning/navigation.git 

2 我的ros版本是kinect-devel,所以clone該版本, 當然,你也可以git clone 之後,git checkout kinect的分支。

  然後將其中的costmap_2d的文件夾copy到 工作區間的src文件夾下方。注意這個地方的,如果是要移植到kinect的機器人上  面,就要在kinect的ros版本環境上編譯, 筆者之前在indigo版本上編譯,把編譯得到的庫挪到kinect的/opt/ros/kinect/lib下,結果報錯

error while loading shared libraries: libXXX.so: cannot open shared object file: No such file or directory

 所以注意,如果編譯得到的庫要移植到kinect上,就要kinect的ros環境下編譯。
3 修改代碼: 打開navigation/costmap_2d/plugins/下的obstacles_layer.cpp 代碼文件
  1. void ObstacleLayer::laserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr& raw_message,  
  2.                                               const boost::shared_ptr<ObservationBuffer>& buffer)  
  3. {  
  4. <span style="color:#FF0000;">  // Filter positive infinities ("Inf"s) to max_range.  
  5.   float epsilon = 0.0001;  // a tenth of a millimeter  
  6.   sensor_msgs::LaserScan message = *raw_message;  
  7.   for (size_t i = 0; i < message.ranges.size(); i++)  
  8.   {  
  9.     float range = message.ranges[ i ]; 
  10. // /修改該地方,因爲我的雷達沒數據時,返回零值,所以判斷當距離等於時,作爲無窮遠點來處理。
  11.     if ((!std::isfinite(range) && (range > 0)) || (range == 0.0))  
  12.     {  
  13.       message.ranges[ i ] = message.range_max - epsilon;  
  14.   
  15.     }  
  16.   
  17.   }</span>  
  18.   
  19.   // project the laser into a point cloud  
  20.   sensor_msgs::PointCloud2 cloud;  
  21.   cloud.header = message.header;  
  22.   
  23.   // project the scan into a point cloud  
  24.   try  
  25.   {  
  26.     projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *tf_);  
  27.   }  
  28.   catch (tf::TransformException &ex)  
  29.   {  
  30.     ROS_WARN("High fidelity enabled, but TF returned a transform exception to frame %s: %s",  
  31.              global_frame_.c_str(), ex.what());  
  32.     projector_.projectLaser(message, cloud);  
  33.   }  
  34.   
  35.   // buffer the point cloud  
  36.   buffer->lock();  
  37.   buffer->bufferCloud(cloud);  
  38.   buffer->unlock();  
  39. }  
3 接下來就是編譯啦。 
catkin_make    // 可以用catkin_make -j2代替,以免樹莓派死機
catkin_make install  就可以在install的文件夾下,得到liblayers.so和libcostmap_2d.so文件。
將以上得到的so文件複製到 /opt/ros/kinect/lib下,然後覆蓋到。
4 關於編譯的一些問題 :
   4.1由於筆者在樹莓派上面編譯,所以特別吃力,所以使用catkin_make -j2 使用雙線程編譯,以免死機,筆者在這地方編譯時,卡了二十幾分鍾才編譯好。
   4.2另外由於在ubuntu上 ,swap空間會比較小,所以 還要設置一下swap空間。以免編譯時出現死機,當然這些問題,PC機都不會出現。 參考如下
  4.3另外 由於,筆者的樹莓派的時間忘記設定,所以 編譯時會報錯 Warning message: Clock skew detected. Yourbuild may be incomplete.這是由於代碼的時間比系統時間來得超前, 所以把時間 往目前時間調,就可以啦。 使用 date -s命令設置系統時間。


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