使用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 ) |
實驗的現象主要如下所表現: 由於解決時,未保存圖,所以圖摘自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
- void ObstacleLayer::laserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr& raw_message,
- const boost::shared_ptr<ObservationBuffer>& buffer)
- {
- <span style="color:#FF0000;"> // Filter positive infinities ("Inf"s) to max_range.
- float epsilon = 0.0001; // a tenth of a millimeter
- sensor_msgs::LaserScan message = *raw_message;
- for (size_t i = 0; i < message.ranges.size(); i++)
- {
- float range = message.ranges[ i ];
- // /修改該地方,因爲我的雷達沒數據時,返回零值,所以判斷當距離等於時,作爲無窮遠點來處理。
- if ((!std::isfinite(range) && (range > 0)) || (range == 0.0))
- {
- message.ranges[ i ] = message.range_max - epsilon;
- }
- }</span>
- // project the laser into a point cloud
- sensor_msgs::PointCloud2 cloud;
- cloud.header = message.header;
- // project the scan into a point cloud
- try
- {
- projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *tf_);
- }
- catch (tf::TransformException &ex)
- {
- ROS_WARN("High fidelity enabled, but TF returned a transform exception to frame %s: %s",
- global_frame_.c_str(), ex.what());
- projector_.projectLaser(message, cloud);
- }
- // buffer the point cloud
- buffer->lock();
- buffer->bufferCloud(cloud);
- buffer->unlock();
- }