机器人导航到某个目标点,此过程需要一个节点A发布目标信息,然后一个节点B接收到请求并控制移动,最终响应目标达成状态信息。

        乍一看,这好像是服务通信实现,因为需求中要A发送目标,B执行并返回结果,这是一个典型的基于请求响应的应答模式,不过,如果只是使用基本的服务通信实现,存在一个问题:导航是一个过程,是耗时操作,如果使用服务通信,那么只有在导航结束时,才会产生响应结果,而在导航过程中,节点A是不会获取到任何反馈的,从而可能出现程序"假死"的现象,过程的不可控意味着不良的用户体验,以及逻辑处理的缺陷(比如:导航中止的需求无法实现)。更合理的方案应该是:导航过程中,可以连续反馈当前机器人状态信息,当导航终止时,再返回最终的执行结果。在ROS中,该实现策略称之为:action 通信。

        在ROS中提供了actionlib功能包集,用于实现 action 通信。action 是一种类似于服务通信的实现,其实现模型也包含请求和响应,但是不同的是,在请求和响应的过程中,服务端还可以连续的反馈当前任务进度,客户端可以接收连续反馈并且还可以取消任务。

python action python action库_开发语言

python action python action库_python_02

 1.定义action文件

        首先新建功能包,并导入依赖: roscpp rospy std_msgs actionlib_msgs

        然后功能包下新建 action 目录,新增 Timer.action。

        action 文件内容组成分为三部分:请求目标值、最终响应结果、连续反馈,三者之间使用---分割示例内容如下:

# This is an action definition file, which has three parts: the goal, the
# result, and the feedback.
#
# Part 1: the goal, to be sent by the client
#
# The amount of time we want to wait
duration time_to_wait
---
# Part 2: the result, to be sent by the server upon completion
#
# How much time we waited
duration time_elapsed
# How many updates we provided along the way
uint32 updates_sent
---
# Part 3: the feedback, to be sent periodically by the server during
# execution.
#
# The amount of time that has elapsed from the start
duration time_elapsed
# The amount of time remaining until we're done
duration time_remaining

2.编辑配置文件CMakeLists.txt

find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
  actionlib_msgs
)
## Generate actions in the 'action' folder
add_action_files(
  FILES
  Timer.action
)

## Generate added messages and services with any dependencies listed here
generate_messages(
  DEPENDENCIES
  actionlib_msgs
  std_msgs
)
catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES demo_action
CATKIN_DEPENDS actionlib_msgs roscpp rospy std_msgs
#  DEPENDS system_lib
)
catkin_install_python(PROGRAMS
  # scripts/simple_action_server.py
  # scripts/simple_action_client.py
  scripts/fancy_action_server.py
  scripts/fancy_action_client.py
  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

3.vscode配置

配置settings.json文件包含python文件所在路径,我的配置如下(主要看第九行

{
    "python.autoComplete.extraPaths": [
        "/home/ssz/demo15_server_client/devel/lib/python2.7/dist-packages",
        "/home/ssz/demo14_pub_sub/devel/lib/python2.7/dist-packages",
        "/home/ssz/demo12_ws/devel/lib/python2.7/dist-packages",
        "/home/ssz/demo09_ws/devel/lib/python2.7/dist-packages",
        "/home/ssz/demo08_ws/devel/lib/python2.7/dist-packages",
        "/opt/ros/melodic/lib/python2.7/dist-packages",
        "/home/ssz/demo18_action/devel/lib/python2.7/dist-packages"
    ],
    "python.analysis.extraPaths": [
        "/home/ssz/demo15_server_client/devel/lib/python2.7/dist-packages",
        "/home/ssz/demo14_pub_sub/devel/lib/python2.7/dist-packages",
        "/home/ssz/demo12_ws/devel/lib/python2.7/dist-packages",
        "/home/ssz/demo09_ws/devel/lib/python2.7/dist-packages",
        "/home/ssz/demo08_ws/devel/lib/python2.7/dist-packages",
        "/opt/ros/melodic/lib/python2.7/dist-packages"
    ]
}

服务端

#! /usr/bin/env python
# -*- coding:utf-8 -*-
import rospy
import time
import actionlib
from demo_action.msg import TimerAction,TimerGoal,TimerResult,TimerFeedback

def do_timer(goal):
        start_time = time.time()
        # 统计总共发布多少反馈信息
        update_count = 0

        if goal.time_to_wait.to_sec() > 60.0:
            result = TimerResult()
            result.time_elapsed = rospy.Duration.from_sec(time.time() - start_time)
            result.updates_sent = update_count
            server.set_aborted(result,"Timer aborted due to too-long wait")
            return
        while (time.time()-start_time) < goal.time_to_wait.to_sec():
            if server.is_preempt_requested():
                result = TimerResult()
                result.time_elapsed = rospy.Duration.from_sec(time.time()-start_time)
                result.updates_sent = update_count
                server.set_preempted(result,"Timer preempted")
                return
            
            feedback = TimerFeedback()
            feedback.time_elapsed = rospy.Duration.from_sec(time.time() - start_time)
            feedback.time_remaining = goal.time_to_wait - feedback.time_elapsed
            server.publish_feedback(feedback)
            update_count += 1
            # 进行短暂的休眠,下面代码采用的“固定休眠时长”方法虽然简单,但其实并不好,
            # 因为这样很容易导致实际休眠时长超过请求时长的问题。
            time.sleep(1.0)
        
        result = TimerResult()
        result.time_elapsed = rospy.Duration.from_sec(time.time() - start_time)
        result.updates_sent = update_count
        # 增加了一个状态字符串
        server.set_succeeded(result,"Timer completed successfully")

rospy.init_node("fancy_action_server")
server = actionlib.SimpleActionServer("timer",TimerAction,do_timer,False)
server.start()
rospy.spin()

客户端

#! /usr/bin/env python
# -*- coding:utf-8 -*-
import rospy
import time
import actionlib
from demo_action.msg import TimerAction,TimerGoal,TimerResult,TimerFeedback

def feedback_cb(feedback):
    print("[Feedback] Time elapsed: %f" %(feedback.time_elapsed.to_sec()))
    print("[Feedback] Time remaining: %f" %(feedback.time_remaining.to_sec()))

rospy.init_node("time_action_client")
client = actionlib.SimpleActionClient("timer",TimerAction)
client.wait_for_server()
goal = TimerGoal()
goal.time_to_wait = rospy.Duration.from_sec(5.0)
# 测试请求时长超过60s的情形
# goal.time_to_wait = rospy.Duration.from_sec(500.0)

# 将回调函数作为feedback-cb关键词的参数,传入send_goal()中,完成回调的注册
client.send_goal(goal,feedback_cb=feedback_cb)

# 测试目标中断
# time.sleep(3.0)
# client.cancel_goal()

client.wait_for_result()
# 在接收到结果之后,我们打印了一些信息来显示当前的状态。get_stste()函数返回本次目标对应的执行结果,
# 类型为actionlib_mags/GoalStatus。可能的状态有10种
# 终端运行rosmsg info actionlib_msgs/GoalStatus命令,看到以下10种
# uint8 PENDING=0
# uint8 ACTIVE=1
# uint8 PREEMPTED=2
# uint8 SUCCEEDED=3
# uint8 ABORTED=4
# uint8 REJECTED=5
# uint8 PREEMPTING=6
# uint8 RECALLING=7
# uint8 RECALLED=8
# uint8 LOST=9
# actionlib_msgs/GoalID goal_id
#   time stamp
#   string id
# uint8 status
# string text
# 此处只考虑其中三种:PREEMPTED=2、SUCCEEDED=3、ABORTED=4
# 除此之外还打印了服务端发送的状态字符串
print("[Result] State: %d" %(client.get_state()))
print("[Result] Status: %s" %(client.get_goal_status_text()))
print("[Result] Time elapsed: %f" %(client.get_result().time_elapsed.to_sec()))
print("[Result] Updates sent: %d" %(client.get_result().updates_sent))

 功能检查

先启动roscore,终端运行下面指令

python action python action库_python action_03

可以看到所有节点运行起来了:等待过程中,每秒会收到一次反馈。等待结束后,会收到目标执行成功的结果(SUCCEED = 3)。

现在试试中断一个执行中的目标。在客户端代码的send_goal()调用后对下面两行解除注释,这样会让客户端在短暂的休眠后中断当前的目标。

# 测试目标中断
# time.sleep(3.0)
# client.cancel_goal()

 再次运行客户端

python action python action库_开发语言_04

表现出的行为与预期吻合:服务器首先执行最开始的目标,并定时进行反馈,直到客户端发出了终止请求。发出终止请求后,客户端很快就收到了服务端发来的结果,表明上一次执行被中断(PREEMPTED = 2)

现在来引发一个服务端的主动终止。在客户端代码中,对下面的代码解除注释,将等待时间从5s改为500s.

# 测试请求时长超过60s的情形
# goal.time_to_wait = rospy.Duration.from_sec(500.0)

再次运行客户端

python action python action库_python_05

服务端立即主动终止了目标的执行(ABORTED = 4)

话题、服务和动作机制的对比

类型

最佳使用场景

话题

单工通信,尤其是接收方有多个时(如传感器数据流)

服务

简单的请求/响应式交互场景,如询问节点的当前状态

动作

大部分请求/响应式交互场景,尤其是执行过程不能立即完成时(如导航前往另一个目标点、机械臂移动)

综合上文中提到的所有特性,动作机制在机器人编程的许多方面都很适合。在机器人应用中,执行一个时长不定,目标引导新的任务是很常见的,无论是goto_position,还是clean_the_house。在任何情况下,当需要执行一个任务时,动作都可能时最正确的选择。事实上,每当你想要使用服务时,都值的考虑一下是否可以替换为动作。虽然使用动作需要写更多的代码,但是却比服务更强大,扩展性更好。