參考 https://blog.csdn.net/qq_23981335/article/details/100335743
1、 定義action
# src/cat1/action/Action1.action 文件路徑
# 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
修改CMakeLists.txt
# src/cat1/CMakeLists.txt
## Generate actions in the 'action' folder
add_action_files(
FILES
Action1.action
# Action2.action
)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
actionlib_msgs
actionlib
message_generation
)
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs
actionlib_msgs
)
修改package.xml
#src/cat1/package.xml 添加以下
<build_depend>actionlib</build_depend>
<build_depend>actionlib_msgs</build_depend>
<exec_depend>actionlib</exec_depend>
<exec_depend>actionlib_msgs</exec_depend>
catkin_make
編譯驗證是否成功
服務(wù)端程序
#!usr/bin/python
# _*_ coding: utf-8 _*_
# @File : service1.py
# @Version : 1.0
# @Author : xin
# @Time : 2021/07/13 15:54:18
# Description:
import rospy
import roslib
import actionlib
from cat1.msg import *
class DishesServer:
def __init__(self):
self.server = actionlib.SimpleActionServer(
"do_dishes", Action1Action, self.execute_dishes, True)
def execute_dishes(self, goal):
i = 0
percent = Action1Feedback()
res = Action1Result()
rate = rospy.Rate(25)
print("execute_dishes")
while i < goal.dishwasher_id:
i += 1
percent.percent_complete = i/float(goal.dishwasher_id)
self.server.publish_feedback(percent)
rate.sleep()
res.total_dishes_cleaned = i
self.server.set_succeeded(res)
if __name__ == "__main__":
print("service...")
rospy.init_node("dishes_server")
server=DishesServer()
rospy.spin()
客戶端程序
#!usr/bin/python
# _*_ coding: utf-8 _*_
# @File : client1.py
# @Version : 1.0
# @Author : xin
# @Time : 2021/07/13 15:42:28
# Description:
import rospy
import roslib
import actionlib
from rospy import client
from cat1.msg import *
def done_callback(state, res):
rospy.loginfo("done_callback state%d dishes:%d",state, res.total_dishes_cleaned)
def action_back():
rospy.loginfo("action_back")
def feedback_callback(fb):
t=int(fb.percent_complete*100);
rospy.loginfo("feedback_callback %d%%",t )
if __name__ == "__main__":
print("client ...")
rospy.init_node("dishces_client")
client = actionlib.SimpleActionClient("do_dishes", Action1Action)
client.wait_for_server()
goal = Action1Goal()
goal.dishwasher_id = 5
client.send_goal(goal, done_callback, action_back, feedback_callback)
client.wait_for_result(rospy.Duration.from_sec(5.0))