Robot Ignite6: actions(动作) part1

action是什么

action跟service非常相似,都需要server跟client。但不像service,client必须等待server给出回应,这期间什么也不能做。actions中client不需要等待server发送消息,某种意义上来说算是异步的service.
这里写图片描述

我们启动一个action server,查看action消息需要使用rostopic list (surprise!),并且会发现action server下面的话题都长的差不多:

/ardrone_action_server/cancel
/ardrone_action_server/feedback
/ardrone_action_server/goal
/ardrone_action_server/result
/ardrone_action_server/status

发现没,action client与server均是靠这五个话题来进行交互。

请求action消息

请求action server的过程就是向server发送消息的过程。这与topic,service消息发送大同小异。让我们回忆一下各自怎么发送消息:

  • topic:对应消息msg,因为topic消息如同广播,没有特定client,只需要使用publisher就能发布某种消息。
  • service: 对应消息srv,service中有server跟client, 在发送消息后还会返回消息处理结果,所以包含两部分:发送给server的输入参数;以及server处理消息后返回的标志信息
  • action: 对应消息action,action跟service相似,具有server,client主从结构。但比service更进一步的是,server不止广播标志信息,同时会做出反馈给client,也就是跟client的交互比service更多。

我们先来看看Ardrone.action消息的结构:

#goal for the drone
int32 nseconds  # the number of seconds the drone will be taking pictures

---
#result
sensor_msgs/CompressedImage[] allPictures # an array containing all the pictures taken along the nseconds

---
#feedback
sensor_msgs/CompressedImage lastImage  # the last image taken

里面的注释解释的很清楚了。但我奇怪的是为什么最后一张照片需要使用feedback返回?

action 里面的feedback如何发挥作用?

因为action的工作机制是异步的,请求action server的时候并不会中断当前线程。这时action server每隔一段时间就发出一个feedback,告诉caller client现在这个动作进行到哪里了。

如何请求action server

我们就下面这个例子来分析如何请求action server:
该代码的目的是调用无人机上的摄像头,按照之前提到的Ardrone.action消息结构,输入秒数,然后不断的报告相应的

#! /usr/bin/env python
import rospy
import time
import actionlib #关于action有一个专门的包来处理相关消息
from ardrone_as.msg import ArdroneAction, ArdroneGoal, ArdroneResult, ArdroneFeedback

nImage = 1

# definition of the feedback callback. This will be called when feedback
# is received from the action server
# it just prints a message indicating a new message has been received
def feedback_callback(feedback):
    global nImage
    print('[Feedback] image n.%d received'%nImage)
    nImage += 1

# initializes the action client node
rospy.init_node('drone_action_client')

# create the connection to the action server
client = actionlib.SimpleActionClient('/ardrone_action_server', ArdroneAction)
# waits until the action server is up and running
client.wait_for_server()

# creates a goal to send to the action server
goal = ArdroneGoal()
goal.nseconds = 10 # indicates, take pictures along 10 seconds

# sends the goal to the action server, specifying which feedback function
# to call when feedback received
client.send_goal(goal, feedback_cb=feedback_callback)

# Uncomment these lines to test goal preemption:
#time.sleep(3.0)
#client.cancel_goal()  # would cancel the goal 3 seconds after starting

# wait until the result is obtained
# you can do other stuff here instead of waiting
# and check for status from time to time 
# status = client.get_state()
# check the client API link below for more info

client.wait_for_result()

print('[Result] State: %d'%(client.get_state()))

注意到,action消息文件叫Ardrone.action。通过编译后,ros会自动生成该action对应的action,goal,result,feedback对象,其名字分别是ArdroneAction, ArdroneGoal, ArdroneResult, ArdroneFeedback. 这些对象都处于packagename.msg库内。

How to perform other tasks while the Action is in progress¶

#! /usr/bin/env python

import rospy
import time
import actionlib
from ardrone_as.msg import ArdroneAction, ArdroneGoal, ArdroneResult, ArdroneFeedback

nImage = 1

# definition of the feedback callback. This will be called when feedback
# is received from the action server
# it just prints a message indicating a new message has been received
def feedback_callback(feedback):
    global nImage
    print('[Feedback] image n.%d received'%nImage)
    nImage += 1


# initializes the action client node
rospy.init_node('example_with_waitforresult_action_client_node')


action_server_name = '/ardrone_action_server'
client = actionlib.SimpleActionClient(action_server_name, ArdroneAction)

# waits until the action server is up and running
rospy.loginfo('Waiting for action Server '+action_server_name)
client.wait_for_server()
rospy.loginfo('Action Server Found...'+action_server_name)


# creates a goal to send to the action server
goal = ArdroneGoal()
goal.nseconds = 10 # indicates, take pictures along 10 seconds

client.send_goal(goal, feedback_cb=feedback_callback)
rate = rospy.Rate(1)

rospy.loginfo("Lets Start The Wait for the Action To finish Loop...")
while not client.wait_for_result():
    rospy.loginfo("Doing Stuff while waiting for the Server to give a result....")
    rate.sleep()

rospy.loginfo("Example with WaitForResult Finished.")

[INFO] [1524135897.964303, 62.899000]: Waiting for action Server /ardrone_action_server
[INFO] [1524135897.995524, 62.915000]: Action Server Found…/ardrone_action_server
[INFO] [1524135897.996480, 62.915000]: Lets Start The Wait for the Action To finish Loop…
[Feedback] image n.1 received
[Feedback] image n.2 received
[Feedback] image n.3 received
[Feedback] image n.4 received
[Feedback] image n.5 received
[Feedback] image n.6 received
[Feedback] image n.7 received
[Feedback] image n.8 received
[Feedback] image n.9 received
[INFO] [1524135924.839178, 71.923000]: Example with WaitForResult Finished.

#! /usr/bin/env python

import rospy
import time
import actionlib
from ardrone_as.msg import ArdroneAction, ArdroneGoal, ArdroneResult, ArdroneFeedback

"""
class SimpleGoalState:
    PENDING = 0
    ACTIVE = 1
    DONE = 2
    WARN = 3
    ERROR = 4

"""
# We create some constants with the corresponing vaules from the SimpleGoalState class
PENDING = 0
ACTIVE = 1
DONE = 2
WARN = 3
ERROR = 4

nImage = 1

# definition of the feedback callback. This will be called when feedback
# is received from the action server
# it just prints a message indicating a new message has been received
def feedback_callback(feedback):
    """
    Error that might jump

    self._feedback.lastImage = 
AttributeError: 'ArdroneAS' obj

    """
    global nImage
    print('[Feedback] image n.%d received'%nImage)
    nImage += 1

# initializes the action client node
rospy.init_node('example_no_waitforresult_action_client_node')

action_server_name = '/ardrone_action_server'
client = actionlib.SimpleActionClient(action_server_name, ArdroneAction)

# waits until the action server is up and running
rospy.loginfo('Waiting for action Server '+action_server_name)
client.wait_for_server()
rospy.loginfo('Action Server Found...'+action_server_name)

# creates a goal to send to the action server
goal = ArdroneGoal()
goal.nseconds = 10 # indicates, take pictures along 10 seconds

client.send_goal(goal, feedback_cb=feedback_callback)


# You can access the SimpleAction Variable "simple_state", that will be 1 if active, and 2 when finished.
#Its a variable, better use a function like get_state.
#state = client.simple_state
# state_result will give the FINAL STATE. Will be 1 when Active, and 2 if NO ERROR, 3 If Any Warning, and 3 if ERROR
state_result = client.get_state()

rate = rospy.Rate(1)

rospy.loginfo("state_result: "+str(state_result))

while state_result < DONE:
    rospy.loginfo("Doing Stuff while waiting for the Server to give a result....")
    rate.sleep()
    state_result = client.get_state()
    rospy.loginfo("state_result: "+str(state_result))

rospy.loginfo("[Result] State: "+str(state_result))
if state_result == ERROR:
    rospy.logerr("Something went wrong in the Server Side")
if state_result == WARN:
    rospy.logwarn("There is a warning in the Server Side")

#rospy.loginfo("[Result] State: "+str(client.get_result()))

[INFO] [1524135955.180295, 81.900000]: Waiting for action Server /ardrone_action_server
[INFO] [1524135955.272857, 81.932000]: Action Server Found…/ardrone_action_server
[INFO] [1524135955.273817, 81.932000]: state_result: 0
[INFO] [1524135955.274263, 81.932000]: Doing Stuff while waiting for the Server to give a result….
[Feedback] image n.1 received
[INFO] [1524135958.362400, 82.932000]: state_result: 1
[INFO] [1524135958.362859, 82.932000]: Doing Stuff while waiting for the Server to give a result….
[Feedback] image n.2 received
[INFO] [1524135961.314678, 83.932000]: state_result: 1
[INFO] [1524135961.315173, 83.932000]: Doing Stuff while waiting for the Server to give a result….
[Feedback] image n.3 received
[INFO] [1524135964.446658, 84.932000]: state_result: 1
[INFO] [1524135964.447105, 84.932000]: Doing Stuff while waiting for the Server to give a result….
[Feedback] image n.4 received
[INFO] [1524135967.362443, 85.932000]: state_result: 1
[INFO] [1524135967.362898, 85.932000]: Doing Stuff while waiting for the Server to give a result….
[Feedback] image n.5 received
[INFO] [1524135970.311845, 86.932000]: state_result: 1
[INFO] [1524135970.312297, 86.932000]: Doing Stuff while waiting for the Server to give a result….
[Feedback] image n.6 received
[INFO] [1524135973.589600, 87.933000]: state_result: 1
[INFO] [1524135973.590087, 87.933000]: Doing Stuff while waiting for the Server to give a result….
[Feedback] image n.7 received
[INFO] [1524135976.613317, 88.932000]: state_result: 1
[INFO] [1524135976.613778, 88.932000]: Doing Stuff while waiting for the Server to give a result….
[Feedback] image n.8 received
[INFO] [1524135979.509011, 89.932000]: state_result: 1
[INFO] [1524135979.509501, 89.932000]: Doing Stuff while waiting for the Server to give a result….
[Feedback] image n.9 received
[INFO] [1524135982.554708, 90.933000]: state_result: 1
[INFO] [1524135982.555190, 90.933000]: Doing Stuff while waiting for the Server to give a result….
[INFO] [1524135985.539898, 91.932000]: state_result: 3
[INFO] [1524135985.540512, 91.932000]: [Result] State: 3
[WARN] [1524135985.540972, 91.932000]: There is a warning in the Server Side

扫描二维码关注公众号,回复: 1027305 查看本文章

猜你喜欢

转载自blog.csdn.net/u010137742/article/details/79935494