當前需求:
問題出現在《[原創]ROS : 參數服務器之動態調參(dynamic_reconfigure)》測試過程中,從激光雷達數據的角度來看,當臨時障礙物與機身相交時,機器人回人爲自己被“卡住”,局部規劃器規劃的速度爲0,機器人停止運動;即使更換新的任何目標點,機器人均停止不動;
還是當前位置,但是重啓整個程序後,設置新的可行的目標點時,機器人能夠抵達目標!!!這個重啓的本質是重啓了move_base,爲保證其他程序還能繼續運行,因此嘗試單獨重啓move_base。利用roslaunch檢測到有新的同名節點時會關閉就的節點並開啓新的節點特性,在新終端執行
roslaunch atrobot_nav move_base
思路:當檢測到存在以上機器人被“卡住”的情況,重啓move_base;
具體步驟:
①觸發條件的判斷
當接收到目標點Goal後,move_base的執行狀態會通過MoveBaseActionResult中的status反饋([原創]actionlib中ActionServer和ActionClient的狀態機),其中當執行結果爲失敗時一般反饋aborted(即status= 4),造成aborted的原因有很多,其中以全局規劃失敗,局部規劃失敗和震盪失敗三種情況爲主(關於三種情況的介紹和震盪的定義,見[原創]從move_base源碼中分析自動導航失敗的三種情況的現象以及處理機制)。以上的這種機器人停止不動會觸發震盪失敗。但觸發震盪失敗檢測必須設定oscillation_timeout和oscillation_distance才能開啓(oscillation_timeout表示執行修復操作之前,允許的震盪時間是幾秒。 值0意味着永不超時)!
move_base.cpp源碼中,當出現震盪信號時,status= 4,且text會被賦值字符串Robot is oscillating. Even after executing recovery behaviors.
else if(recovery_trigger_ == OSCILLATION_R){ //局部規劃修復發生了震盪
ROS_ERROR("Aborting because the robot appears to be oscillating over and over. Even after executing all recovery behaviors");
as_->setAborted(move_base_msgs::MoveBaseResult(), "Robot is oscillating. Even after executing recovery behaviors.");
因此,可以通過判斷status和text的內容來判斷是否出現以上現象!!!具體代碼示例如下:
string str_oscillating_err = "Robot is oscillating. Even after executing recovery behaviors.";
... ...
if(msg->status.status == ABORTED)
{
... ...
else if(str_get == str_oscillating_err)
{
ROS_INFO("move_base cmd_vel oscillating fail.");
.....
}
... ...
}
②在C++中執行重啓move_base
這就是在c++代碼裏面調用shell指令問題(原理參見《c,c++中調用shell腳本並保存shell的執行結果》)這裏選用popen()方便看看打印信息。
- a.封裝popen()
/*********C++執行.sh的API接口函數**********/
std::string exec(const char* cmd) {
char buffer[128];
std::string result = "";
FILE* pipe = popen(cmd, "r");
if (!pipe) throw std::runtime_error("popen() failed!");
try {
while (fgets(buffer, sizeof buffer, pipe) != NULL) {
result += buffer;
}
} catch (...) {
pclose(pipe);
throw;
}
pclose(pipe);
return result;
}
代碼解釋:
exec爲自定義的API程序,將管道創建和關閉封裝成一個應用;
popen(cmd, "r"),創建一個管道,通過fork或者invoke一個子進程,然後執行command,r表示command從管道中讀取數據流(而w表示command的stdout輸出到管道中)。
- b.封裝後API的調用
else if(str_get == str_oscillating_err)
{
ROS_INFO("move_base cmd_vel oscillating fail.");
navi_status.state = 43; //ABORTED_LOCAL
/*********重啓move_base*********/
exec("/home/firefly/eai_ws/src/motion/navigation_goal/sh/reboot_move_base.sh");
}
調用時需要引號和shell文件的完整路徑;
- c.shell程序編寫
已以上路徑下新建一個文件
touch reboot_move_base.sh
編輯內容
vim reboot_move_base.sh
修改文件權限
chmod a+x reboot_move_base.sh
③編譯執行
拓展應用:
類似看門狗程序,實時監測話題或服務是否運行,若異常停止重啓對應的包!!