SimpleActionClient端(Python)
SimpleActionClient创建流程
1. 创建Node节点
| rospy.init_node(nodeName, anonymous=True)
|
2. 创建SimpleActionClient
| client = actionlib.SimpleActionClient(actionName, CountNumberAction)
client.wait_for_server()
|
Tip
我们需要引入actionlib这个依赖库,添加模块导入
import actionlib
actionlib.SimpleActionClient
: Action的Client端
对应的类。
第一个参数:当前action的名称
第二个参数:当前action的消息类型
3. 发送Goal指令给Server端
| goal = CountNumberGoal(max=100, duration=0.5)
client.send_goal(goal, done_cb=done_cb, active_cb=active_cb, feedback_cb=feedback_cb)
|
Tip
def send_goal(self, goal, done_cb=None, active_cb=None, feedback_cb=None)
send_goal
函数,对应了几个参数。
第一个参数goal: 对应的是发送的指令数据,server端
会根据客户端的数据进行对应的逻辑。
第二个参数done_cb:server端
完成耗时操作时,告知客户端的回调。
第三个参数active_cb: server端
在执行操作过程中,告知客户端的开始执行任务的回调。
第四个参数feedback_cb: server端
在执行操作过程中,告知客户端的进度回调。
4.完成回调
结果回调
| def done_cb(state, result):
rospy.loginfo(state)
rospy.loginfo(result)
if state == GoalStatus.ABORTED:
rospy.loginfo("server working error, don't finish my job.")
elif state == GoalStatus.PREEMPTED:
rospy.loginfo("client cancel job.")
elif state == state.SUCCEEDED:
rospy.loginfo("server finish job.")
rospy.loginfo("result: %f" % result.count)
|
开始回调
| def active_cb():
rospy.loginfo("active callback")
|
进度回调
| def feedback_cb(feedback):
rospy.loginfo(feedback)
|
完整代码
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48 | #!/usr/bin/env python
# coding:utf-8
import rospy
import actionlib
from actionlib import GoalStatus
from demo_actions.msg import CountNumberAction, CountNumberGoal, CountNumberResult
def done_cb(state, result):
rospy.loginfo(state)
rospy.loginfo(result)
if state == GoalStatus.ABORTED:
rospy.loginfo("server working error, don't finish my job.")
elif state == GoalStatus.PREEMPTED:
rospy.loginfo("client cancel job.")
elif state == state.SUCCEEDED:
rospy.loginfo("server finish job.")
rospy.loginfo("result: %f" % result.count)
def active_cb():
rospy.loginfo("active callback")
def feedback_cb(feedback):
rospy.loginfo(feedback)
if __name__ == '__main__':
nodeName = "CountNumberClint"
actionName = "/count_number"
# 创建节点
rospy.init_node(nodeName, anonymous=True)
# 创建客户端
client = actionlib.SimpleActionClient(actionName, CountNumberAction)
# 等待连接服务器
client.wait_for_server()
# 发送请求
goal = CountNumberGoal(max=100, duration=0.5)
client.send_goal(goal, done_cb=done_cb, feedback_cb=feedback_cb)
rospy.spin()
|
调试Client端
通过现有的server
端进行调试。