Action响应结果(Python)

Action状态变化

Action通讯的状态按照执行流程分为以上几种。在这几种状态中,有做了一下细分,如下图:

server端在处理状态的过程种,会将所有的状态拆分为常用的两种:ActiveDone

  • Active为激活状态。

  • DoneSucceedPreemptedAbortedRejected几种状态的统称。代表了当前任务已经执行完成。

  • Succeed:server端成功完成client的需求,将成功结果返回。
  • Preempted:server端在在执行过程中,client端取消了执行指令,server端将取消的结果返回。
  • Aborted:server端在执行过程中,自身出现了状况,没有完成任务,将结果反馈给client端。

Active和Done状态的分流处理

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
def transition_cb(goal_handle):
    rospy.loginfo("---------------transition cb---------------")
    state = goal_handle.get_comm_state()

    if state == CommState.ACTIVE:
        rospy.loginfo("ACTIVE")
    elif state == CommState.DONE:
        rospy.loginfo("DONE")
        done_state = goal_handle.get_terminal_state()
        result = goal_handle.get_result()
        done_cb(done_state, result)

Tip

server端状态反馈结果都会回调到client端的transition_cb回调中来。通常我们通过以上代码进行状态的判断和分流。

以上第3行中,我们可以通过goalHanle获得状态CommState,CommState可以有效的进行分流判断。

以上第5行中,我们可以通过goalHanle获得状态TerminalStateTerminalState就是Done的四种状态之一。

以上第7行中,我们可以通过goalHanle获得server端处理的结果,根据实际情况,我们可以定义函数done_cb来处理结果。

Done状态中,done_cb可以继续的进行状态的判断分流,结果如下:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
def done_cb(state, result):
    rospy.loginfo(state)
    rospy.loginfo(result)

    if state == TerminalState.ABORTED:
        rospy.loginfo("server working error, don't finish my job.")
    elif state == TerminalState.PREEMPTED:
        rospy.loginfo("client cancel job.")
    elif state == TerminalState.SUCCEEDED:
        rospy.loginfo("server finish job.")
        rospy.loginfo("result: %f" % result.count)
    elif state == TerminalState.REJECTED:
        rospy.loginfo("server rejected job.")

Tip

以上就可以进行多种状态分流,进行自己的业务逻辑了。

## Succeed结果反馈实现

Succeed状态说由server端反馈给client端的,因此我们只需要保证server端正常运行即可。server端代码如下:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
def goal_cb(goal_handle):
    goal = goal_handle.get_goal()
    # 获得请求数据
    max = goal.max
    duration = goal.duration

    # 将状态修改为Active
    goal_handle.set_accepted()

    rate = rospy.Rate(1.0 / duration)
    count = 0
    while not rospy.is_shutdown() and count < max:
        # 发送进度反馈
        feedback = CountNumberFeedback()
        feedback.percent = count * 100.0 / max
        goal_handle.publish_feedback(feedback)

        rate.sleep()
        count += 1

    # 发送结果反馈
    result = CountNumberResult(count=count)
    goal_handle.set_succeeded(result)

Tip

goal_handle可以获得goal数据,这个是客户端传递的goal指令数据。

在执行过程种,默认的状态还是PENDING,我们需要通过goalHandle.setAccepted();将状态切换为ACTIVE

Preempted结果反馈实现

Preempted状态说由server端反馈给client端的,但是前提是client端发出了取消的指令。

client端发送取消指令操作代码如下:

1
goal_handle.cancel()

server端处理取消判断的逻辑,通常我们会定义一个字典,在cancel_cb取消回调中去记录取消的goal,代码如下:

1
2
3
4
5
6
def cancel_cb(goal_handle):
    rospy.loginfo("---------------cancel cb---------------")
    goal_id = goal_handle.get_goal_id()

    if goal_id in cancel_goals:
        cancel_goals[goal_id] = True

Tip

goal_handle可以获得goal的唯一标识id。

如果取消就记录下来。

server端处理取消判断代码如下:

 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
def goal_cb(goal_handle):
    goal = goal_handle.get_goal()
    goal_id = goal_handle.get_goal_id()
    # 获得请求数据
    max = goal.max
    duration = goal.duration
    # 将状态修改为Active
    goal_handle.set_accepted()

    rate = rospy.Rate(1.0 / duration)
    count = 0
    is_preempted = False
    while not rospy.is_shutdown() and count < max:
        if cancel_goals[goal_id]:
            is_preempted = True
            rospy.loginfo("is preempted")
            break

        feedback = CountNumberFeedback()
        feedback.percent = count * 100.0 / max
        goal_handle.publish_feedback(feedback)

        rate.sleep()
        count += 1

    # 发送结果
    result = CountNumberResult(count=count)
    if is_preempted:
        rospy.loginfo("cancel")
        goal_handle.set_canceled(result)
    else:
        goal_handle.set_succeeded(result)

Tip

以上高亮部分是判断用户是否取消的逻辑,以及取消后的判断操作

Aborted结果响应

Aborted状态说由server端反馈给client端的,但是前提是server端因为自身业务逻辑或者是出现了不可完成的异常导致的结果。server端代码如下:

 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
def goal_cb(goal_handle):
    goal = goal_handle.get_goal()
    goal_id = goal_handle.get_goal_id()
    # 获得请求数据
    max = goal.max
    duration = goal.duration
    # 将状态修改为Active
    goal_handle.set_accepted()

    rate = rospy.Rate(1.0 / duration)
    count = 0
    is_preempted = False
    is_aborted = False
    while not rospy.is_shutdown() and count < max:
        if cancel_goals[goal_id]:
            is_preempted = True
            rospy.loginfo("is preempted")
            break
        if count > 30:
            is_aborted = True
            break
        feedback = CountNumberFeedback()
        feedback.percent = count * 100.0 / max
        goal_handle.publish_feedback(feedback)

        rate.sleep()
        count += 1

    # 发送结果
    result = CountNumberResult(count=count)
    if is_preempted:
        rospy.loginfo("cancel")
        goal_handle.set_canceled(result)
    elif is_aborted:
        rospy.loginfo("aborted")
        goal_handle.set_aborted(result)
    else:
        goal_handle.set_succeeded(result)

Tip

代码高亮第一部分,我们模拟server端处理过程中,无法完成任务而退出。

第二部分则是如何将状态响应给client端

Rejected结果反馈实现

Rejected状态说由server端反馈给client端的,但是前提是server端因为client端发送的goal数据不符合自身要求,拒绝了client请求的结果。server端代码如下:

 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
def goal_cb(goal_handle):
    goal = goal_handle.get_goal()
    goal_id = goal_handle.get_goal_id()
    # 获得请求数据
    max = goal.max
    duration = goal.duration
    # 将当前状态进行修改
    if max < 0:
        goal_handle.set_rejected();
        return
    # 将状态修改为Active
    goal_handle.set_accepted()

    rate = rospy.Rate(1.0 / duration)
    count = 0
    is_preempted = False
    is_aborted = False
    while not rospy.is_shutdown() and count < max:
        if cancel_goals[goal_id]:
            is_preempted = True
            rospy.loginfo("is preempted")
            break
        if count > 30:
            is_aborted = True
            break
        feedback = CountNumberFeedback()
        feedback.percent = count * 100.0 / max
        goal_handle.publish_feedback(feedback)

        rate.sleep()
        count += 1

    # 发送结果
    result = CountNumberResult(count=count)
    if is_preempted:
        rospy.loginfo("cancel")
        goal_handle.set_canceled(result)
    elif is_aborted:
        rospy.loginfo("aborted")
        goal_handle.set_aborted(result)
    else:
        goal_handle.set_succeeded(result)

Tip

代码高亮块部分,是在PENDING状态改变为ACTIVE状态前,先去校验client传入的goal数据是否符合自己处理的逻辑。

并发处理

python本身client不会阻塞,我们只需要修改server端为多线程即可.

1
2
3
4
5
6
def goal_cb(goal_handle):
    rospy.loginfo("---------------goal cb---------------")
    cancel_goals[goal_handle.get_goal_id()] = False

    thread = threading.Thread(name="worker", target=callback, args=(goal_handle,))
    thread.start()