參考
wiki 流網絡 flow network 解釋
相關文章
ipa 分區算法?ipa 分區算法總結,部分算法圖解
環境
ubuntu20,ros 版本 noetic
運行測試
按照 readme 提示進行測試,跳過第一個步驟,并不需要 turtlebot3。
執行第三個 launch 報錯:
看下 room_exploration_client.launch
文件
<?xml version="1.0"?>
<launch><arg name="env_pack" default="$(find cob_default_env_config)" /><arg name="robot_env" default="$(optenv ROBOT_ENV !!NO_ROBOT_ENV_SET!!)"/><arg name="robot_radius" default="0.5"/><arg name="coverage_radius" default="0.5"/><arg name="use_test_maps" default="true"/><!-- --><node ns="room_exploration" pkg="ipa_room_exploration" type="room_exploration_client" name="room_exploration_client" output="screen"><rosparam file="$(arg env_pack)/envs/$(arg robot_env)/map.yaml" command="load" /><param name="env_pack" value="$(arg env_pack)"/><param name="robot_env" value="$(arg robot_env)"/><param name="robot_radius" value="$(arg robot_radius)"/><param name="coverage_radius" value="$(arg coverage_radius)"/><param name="use_test_maps" value="$(arg use_test_maps)"/></node></launch>
env_pack:ipa 的配置功能包,實踐中將程序和系統配置分離,相關功能配置可能是在項目中專門配置功能包中。
robot_env:機器環境,在 env_pack 包中,對多個機器(差速輪底盤,阿克曼底盤等)有多個不同的配置,需要根據機器分別配置參數。
robot_radius:???作用
coverage_radius:機器的覆蓋半徑。
use_test_maps:是否用 ipa 官方的測試地圖。
默認的配置功能包是 cob_default_env_config ,我們自己的項目中不存在這個功能包,所以要創建一個新功能包來完成 ipa 配置功能包即可。
在 ipa_coverage_planning 文件包內創建 ipa_env 功能包,用 tree 查看目錄如下
? ipa_coverage_planning git:(develop) ? tree -L 1
.
├── ipa_building_msgs
├── ipa_building_navigation
├── ipa_coverage_planning
├── ipa_env
├── ipa_room_exploration
├── ipa_room_segmentation
└── README.md
ipa_env 包目錄如下:
第 3 個 launch 指令執行需要修改 env_pack 參數值,如下:
roslaunch ipa_room_exploration room_exploration_client.launch env_pack:=ipa_env robot_env:=ipa_robot use_test_maps:=false
執行后依舊報錯:
把 room_exploration_client.launch 的 env_pack 默認值修改為存在的其他功能包名,如下:
<arg name="env_pack" default="$(find ipa_room_exploration)" />
執行后沒有“not found cob_default_env_config” 的錯誤了。
!!!注意!!!
這里說明 xml 中標簽 <arg> 的默認值執行是在終端賦值之前的執行的!
但有了其他問題,rosparam 找不到 map.yaml 文件:
在 map.yaml 文件目錄下執行 pwd 查看路徑:
路徑是正確的。
仔細看看 xml,發現 file 是用 $(arg env_pack) 拼接的,說明變量 env_pack 需要包含 ipa 配置功能包在系統中的絕對路徑,而我們的傳參僅僅傳遞了 ipa 配置功能包名。
修改 launch 如下,讓 file 自動尋找 env_pack 功能包在系統的絕對路徑,下面只顯示修改的部分:
<arg name="env_pack" default="ipa_room_exploration" /><node ns="room_exploration" pkg="ipa_room_exploration" type="room_exploration_client" name="room_exploration_client" output="screen"><rosparam file="$(find $(arg env_pack))/envs/$(arg robot_env)/map.yaml" command="load" /><param name="env_pack" value="$(find env_pack)"/></node>
再執行 launch,map.yaml 文件已經可以找到了,但出現新問題,xml 中 $() 不讓嵌套使用,報語法錯誤。゚(TヮT)゚。
最后還是改成下面這樣:
<?xml version="1.0"?>
<launch><arg name="env_pack" default="$(find ipa_env)" /><arg name="robot_env" default="$(optenv ROBOT_ENV !!NO_ROBOT_ENV_SET!!)"/><arg name="robot_radius" default="0.5"/><arg name="coverage_radius" default="0.5"/><arg name="use_test_maps" default="true"/><!-- --><node ns="room_exploration" pkg="ipa_room_exploration" type="room_exploration_client" name="room_exploration_client" output="screen"><rosparam file="$(arg env_pack)/envs/$(arg robot_env)/map.yaml" command="load" /><param name="env_pack" value="$(arg env_pack)"/><param name="robot_env" value="$(arg robot_env)"/><param name="robot_radius" value="$(arg robot_radius)"/><param name="coverage_radius" value="$(arg coverage_radius)"/><param name="use_test_maps" value="$(arg use_test_maps)"/></node></launch>
執行 launch 也不需要修改 env_pack 變量值了:
roslaunch ipa_room_exploration room_exploration_client.launch robot_env:=ipa_robot use_test_maps:=false
程序運行成功!


覆蓋算法測試
ipa_room_exploration/ros/launch/room_exploration_action_server_params.yaml
文件中的 room_exploration_algorithm
參數來選擇覆蓋算法。重啟 ipa 服務端,重新加載參數,執行
roslaunch ipa_room_exploration room_exploration_action_server.launch
執行后發現覆蓋路徑無明顯變化。
服務端 log 如下:
log 顯示啟動 server.launch 后,覆蓋算法已經修改為 6 局部能量最小覆蓋算法。
注意這里的 room_exploration/path_planning_algorithm 的 room_exploration 并非參數空間前綴,而是代碼這么寫的。一開始還被誤導以為是參數空間名對不上導致的問題。
之后再啟動 client.launch,觸發了動態參數服務器,將覆蓋算法改為了 8,牛耕算法變種。
在 ipa_room_exploration/ros/src/room_exploration_action_client.cpp 的 121 行發現這段代碼,這里創建了動態參數服務器的客戶端,修改了參數:
屏蔽這段代碼,編譯 ipa_room_exploration 功能包,重新執行服務器 launch 和客戶端 launch。
成功執行了局部能量最小覆蓋算法!

下面展示所有的覆蓋算法路徑效果,這里的測試僅修改了 room_exploration_algorithm
服務器參數,其他參數是官方默認參數。
-
room_exploration_algorithm 參數值之 grid point explorator
對應論文的 Grid-based Traveling Salesman Coverage Path Planning 基于柵格旅行商覆蓋路徑算法,用 TSP 旅行商算法來計算地圖中所有空閑柵格的遍歷順序。
該算法十分耗時,作者甚至給它做了個進度條,用一張 gif 來感受一下有多慢:

-
room_exploration_algorithm 參數值之 boustrophedon explorator
對應論文的 Boustrophedon Coverage Path Planning 牛耕覆蓋路徑算法

-
room_exploration_algorithm 參數值之 neural network explorator
神經網絡覆蓋算法

-
room_exploration_algorithm 參數值之 convexSPP explorator
Convex Sensor Placement Coverage Path Planning 凸傳感器放置覆蓋路徑算法
Log 有點多 ...

-
room_exploration_algorithm 參數值之 flowNetwork explorator
論文參考文獻和源碼中都找不到相關論文。注釋有這么一句:
This class provides a coverage path planning algorithm based on a flow network.
Wiki 對流網絡 flow network 的解釋如下(有些資料叫 network flow 網絡流):
在圖論中,流網絡是一個有向圖,每條邊都有一個容量,每條邊接收一個流。邊的流量不能超過邊的容量。在運籌學 operations research 中,有向圖通常稱為網絡,頂點稱為節點,邊稱為弧。流必須滿足流入節點的流量等于流出節點的流量的限制,除非它是只有流出的源 S,或者只有流入的匯 t。

Log 刷屏非常多,似乎在第三方庫中,源碼搜索不到相關日志。程序陷入死循環一直沒有結束,該算法應該未完成。
-
room_exploration_algorithm 參數值之 energyFunctional explorator
對應論文 Grid-based Local Energy Minimization 基于柵格的局部能量最小算法

-
room_exploration_algorithm 參數值之 voronoi explorator
對應論文 Contour Line-based Coverage Path Planning 基于輪廓線的覆蓋路徑算法
執行后沒有規劃成功,服務端 log:
把服務器參數 revisit_areas
設置為 true,再次測試...還是規劃失敗。
客戶端 log:
沒有其他 log 提示了,初步判斷是地圖沒有封閉空間導致的,給地圖增加一圈黑邊(障礙物)再測試。
規劃成功!說明用 voronoi explorator 算法需要地圖有封閉邊界!

-
room_exploration_algorithm 參數值之 boustrophedon variant explorator
牛耕法變種,改進了牛耕法中細胞分解后,對相同主軸的分區進行合并,減少區域的碎片化。沒找到對應的論文信息。

分區算法測試
分區算法在 ipa_room_segmentation 功能包中,也是分為客戶端和服務端兩部分運行:
服務端 room_segmentation_action_server.launch 和客戶端 room_segmentation_action_client.launch
分區算法的參數配置在 ipa_room_segmentation/ros/launch/room_segmentation_action_server_params.yaml 中。
同樣,客戶端代碼也修改了動態參數服務器的參數,先屏蔽了 ipa_room_segmentation/ros/src/room_segmentation_client.cpp 的部分代碼:
編譯后分別運行服務端和客戶端的 launch。
測試的地圖不對,測試的還是官方的測試地圖:

而我的地圖是:

從 log 看參數配置的生效了。再看看分區客戶端代碼是怎么寫的...
客戶端是直接把測試地圖名寫入一個 vector 變量 map_names 中,然后在 for 循環中在指定地址獲取相應的地圖地址,把地圖轉為地圖話題數據,再裝入 goal 中發送給服務端。
流程大概如下:
int main(int argc, char **argv)
{ros::init(argc, argv, "room_segmentation_client");ros::NodeHandle nh;// map namesstd::vector< std::string > map_names;map_names.push_back("lab_ipa"); // 這就是測試的第一張默認地圖map_names.push_back("lab_c_scan");... // 加了很多地圖for (size_t image_index = 0; image_index<map_names.size(); ++image_index) {// 在 ipa_room_segmentation 功能包的指定位置搜索地圖std::string image_filename = ros::package::getPath("ipa_room_segmentation") + "/common/files/test_maps/" + map_names[image_index] + ".png";cv::Mat map = cv::imread(image_filename.c_str(), 0); // cv 讀地圖...cv_image.toImageMsg(labeling); // 數據轉換actionlib::SimpleActionClient<ipa_building_msgs::MapSegmentationAction> ac("room_segmentation_server", true);... // goal 數據裝包ac.sendGoal(goal); // 目標發送到服務端bool finished_before_timeout = ac.waitForResult(ros::Duration()); // 等待結果if (finished_before_timeout) {... // 數據轉換到 cv 格式cv::imshow("segmentation", colour_segmented_map); // cv 顯示地圖cv::waitKey(); // 敲空格測試下一張地圖}} // forreturn 0;
}
所以只需要修改客戶端的測試地圖名稱和測試地圖所在的路徑即可。
根據自己的測試環境修改這兩部分代碼,編譯后測試 ok。
下面展示所有的分割算法分區效果,這里的測試僅修改了 room_segmentation_algorithm
服務器參數,其他參數是官方默認參數。
-
room_segmentation_algorithm 參數值之 morphological segmentation
對應論文的 Morphological Segmentation 形態分割算法

-
room_segmentation_algorithm 參數值之 distance segmentation
對應論文 Distance Transform-based Segmentation 距離變換分割算法

-
room_segmentation_algorithm 參數值之 Voronoi segmentation
對應論文 Voronoi Graph-based Segmentation Voronoi 圖分割算法

-
room_segmentation_algorithm 參數值之 semantic segmentation
在《Room Segmentation: Survey, Implementation, and Analysis.》稱為Feature-based Segmentation 特征/語義分割

-
room_segmentation_algorithm 參數值之 voronoi random field segmentation
對應論文 Voronoi Random Fields Segmentation Voronoi 隨機勢場分割

-
room_segmentation_algorithm 參數值之 passthrough segmentation
不分割算法,正如其名...
