actionlib是ROS中一個很重要的功能包集合,盡管在ROS中已經提供了srevice機制來滿足請求—響應式的使用場景,但是假如某個請求執行時間很長,在此期間用戶想查看執行的進度或者取消這個請求的話,service機制就不能滿足了,但是actionlib可滿足用戶這種需求。例如,控制機器人運動到地圖中某一目標位置,這個過程可能復雜而漫長,執行過程中還可能強制中斷或反饋信息,這時actionlib就能大展伸手了。
actionlib使用client-server工作模式,ActionClient 和ActionServer通過"ROS Action Protocol"進行通信,"ROS Action Protocol"以ROS消息方式進行傳輸。此外ActionClient 和ActionServer給用戶提供了一些簡單的接口,用戶使用這些接口可以完成goal請求(client-side)和goal執行(server-side)。
ActionClient 和ActionServer之間使用action protocol通信,action protocol就是預定義的一組ROS message,這些message被放到ROS topic上在 ActionClient 和ActionServer之間進行傳實現二者的溝通。
ROS Messages:
-
goal - Used to send new goals to servers. 代表一個任務,可以被ActionClient發送到ActionServer。比如在MoveBase中,它的類型是PoseStamped,包含了機器人運動目標位置的信息。
-
cancel - Used to send cancel requests to servers
-
status - Used to notify clients on the current state of every goal in the system
-
feedback - Used to send clients periodic auxiliary information for a goal. 服務端定期告知Client當前Goal執行過程中的情況。在Move Base案例中,它表示機器人當前姿態。
-
result - Used to send clients one-time auxiliary information upon completion of a goal
ROS系統在action文件(文件名后綴為.action)中定義了上述goal、result、feedback等消息。The .action file has the goal definition, followed by the result definition, followed by the feedback definition, with each section separated by 3 hyphens (---).
下面是一個示意的例子,在./action/DoDishes.action文件中對洗碗這一任務進行定義:goal為使用某一洗碗機洗碗,result為總共洗好的碗數目,feedback為洗碗進度。
# Define the goal uint32 dishwasher_id # Specify which dishwasher we want to use --- # Define the result uint32 total_dishes_cleaned --- # Define a feedback message float32 percent_complete
下面在catkin_ws/src目錄下創建一個測試package:
catkin_create_pkg actionlib_test roscpp std_msgs actionlib actionlib_msgs message_generation rospy
在package的CMakeLists.txt文件中加入下面這幾行:
#find_package(catkin REQUIRED genmsg actionlib_msgs actionlib) add_action_files(DIRECTORY action FILES DoDishes.action) generate_messages(DEPENDENCIES actionlib_msgs)
注意如果使用catkin_create_pkg創建包時沒有添加actionlib相關的依賴項,要將上面CMakeLists中第一行的注釋去掉,另外還要在package.xml文件中加入下面幾行。因為我們在創建包時就添加好了相關依賴,所以這一步驟可以省略。
<build_depend>actionlib</build_depend> <build_depend>actionlib_msgs</build_depend> <run_depend>actionlib</run_depend> <run_depend>actionlib_msgs</run_depend>
使用catkin_make編譯即可查看生成的消息文件,這些消息之后將會用於ActionClient 和 ActionServer間的通信。
另外可以看到,在devel/include/actionlib_test/中生成了相關的頭文件:
C++ SimpleActionClient
client示例代碼client.cpp如下,它會等待Server連接,發送Goal,獲取狀態。SimpleActionClient完整的API可以參考C++ SimpleActionClient
#include <actionlib_test/DoDishesAction.h> #include <actionlib/client/simple_action_client.h> typedef actionlib::SimpleActionClient<actionlib_test::DoDishesAction> Client; int main(int argc, char** argv) { ros::init(argc, argv, "do_dishes_client"); Client client("do_dishes", true); // true -> don't need ros::spin() client.waitForServer(); // Waits for the ActionServer to connect to this client actionlib_test::DoDishesGoal goal; // Fill in goal here client.sendGoal(goal); // Sends a goal to the ActionServer client.waitForResult(ros::Duration(5.0)); // Blocks until this goal finishes if (client.getState() == actionlib::SimpleClientGoalState::SUCCEEDED) printf("Yay! The dishes are now clean\n"); printf("Current State: %s\n", client.getState().toString().c_str()); return 0; }
C++ SimpleActionServer
服務端代碼server.cpp如下,SimpleActionServert完整的API可以參考 C++ SimpleActionServer
#include <actionlib_test/DoDishesAction.h> #include <actionlib/server/simple_action_server.h> typedef actionlib::SimpleActionServer<actionlib_test::DoDishesAction> Server; void execute(const actionlib_test::DoDishesGoalConstPtr& goal, Server* as) { // Do lots of awesome groundbreaking robot stuff here as->setSucceeded(); } int main(int argc, char** argv) { ros::init(argc, argv, "do_dishes_server"); ros::NodeHandle n; Server server(n, "do_dishes", boost::bind(&execute, _1, &server), false); server.start(); ros::spin(); return 0; }
在CMakeLists文件中加入下面這幾行:
add_executable(client src/client.cpp) add_executable(server src/server.cpp) target_link_libraries( client ${catkin_LIBRARIES}) target_link_libraries( server ${catkin_LIBRARIES})
使用catkin_make進行編譯完成后輸入指令rosrun actionlib_test server 運行server,通過rostopic list查看系統中的話題如下:
使用rqt_graph命令可以查看節點和消息的關系,可以看出server端會接收goal和cancel消息,並發出status、result、feedback消息:
接着輸入指令rosrun actionlib_test client 運行client,結果如下圖所示:
Python SimpleActionClient
除了C++也可以使用Python實現同樣的功能,client.py如下(API可以參考Python SimpleActionClient):
#! /usr/bin/env python import roslib roslib.load_manifest('actionlib_test') import rospy import actionlib from actionlib_test.msg import DoDishesAction, DoDishesGoal if __name__ == '__main__': rospy.init_node('do_dishes_client') client = actionlib.SimpleActionClient('do_dishes', DoDishesAction) client.wait_for_server() goal = DoDishesGoal() # Fill in the goal here client.send_goal(goal) client.wait_for_result(rospy.Duration.from_sec(5.0))
Python SimpleActionServer
server.py程序如下(API可參考Python SimpleActionServer):
#! /usr/bin/env python import roslib roslib.load_manifest('actionlib_test') import rospy import actionlib from actionlib_test.msg import DoDishesAction class DoDishesServer: def __init__(self): self.server = actionlib.SimpleActionServer('do_dishes', DoDishesAction, self.execute, False) self.server.start() def execute(self, goal): # Do lots of awesome groundbreaking robot stuff here self.server.set_succeeded() if __name__ == '__main__': rospy.init_node('do_dishes_server') server = DoDishesServer() rospy.spin()
注意在運行程序前先用chmod +x命令給Python文件添加可執行權限:
運行client.py和server.py,注意client.py運行就會返回:
參考: