[Documentation] [TitleIndex] [WordIndex

  Show EOL distros: 

common: actionlib | bfl | bond | bondcpp | bondpy | filters | nodelet | nodelet_topic_tools | pluginlib | smclib | tinyxml | xacro | yaml_cpp

Package Summary

The actionlib package provides a standardized interface for interfacing with preemptible tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

common: actionlib | bfl | tinyxml | yaml_cpp

Package Summary

The actionlib package provides a standardized interface for interfacing with preemptible tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

actionlib

Package Summary

The actionlib package provides a standardized interface for interfacing with preemptible tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

  • Maintainer status: maintained
  • Maintainer: Dirk Thomas <dthomas AT osrfoundation DOT org>
  • Author: Eitan Marder-Eppstein, Vijay Pradeep
  • License: BSD
  • Source: git https://github.com/ros/actionlib.git (branch: groovy-devel)

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

  • Maintainer status: maintained
  • Maintainer: Esteve Fernandez <esteve AT osrfoundation DOT org>
  • Author: Eitan Marder-Eppstein, Vijay Pradeep
  • License: BSD
  • Source: git https://github.com/ros/actionlib.git (branch: hydro-devel)
ros_base: actionlib | bond_core | class_loader | dynamic_reconfigure | nodelet_core | pluginlib | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

ros_base: actionlib | bond_core | class_loader | dynamic_reconfigure | nodelet_core | pluginlib | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

ros_base: actionlib | bond_core | class_loader | dynamic_reconfigure | nodelet_core | pluginlib | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

ros_base: actionlib | bond_core | class_loader | dynamic_reconfigure | nodelet_core | pluginlib | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

ros_base: actionlib | bond_core | dynamic_reconfigure | nodelet_core | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

ros_base: actionlib | bond_core | dynamic_reconfigure | nodelet_core | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

English

简体中文

概述

在任何大型的基于ROS的系统中,都有这样的情况:有人想向某个节点发送请求,以执行某些任务,并接收对请求的应答。这可以通过ROS服务来实现。

但是,在某些情况下,如果服务需要很长时间执行,用户可能希望在执行过程中取消请求,或者得到关于请求进展情况的定期反馈。actionlib包提供了创建服务器的工具,这些服务器执行可被抢占的长期目标。它还提供了一个客户端接口,以便向服务器发送请求。

详细描述

关于actionlib如何"在后台"操作的完整讨论,请参见详细描述

客户端-服务器交互

ActionClientActionServer通过"ROS行为协议"进行通信,该协议是建立在ROS消息之上的。然后,客户机和服务器为用户提供一个简单的API,用于请求目标(在客户端)或通过函数调用和回调执行目标(在服务器端)。

client_server_interaction.png

行为规范: Goal, Feedback, & Result

为了让客户机和服务器进行通信,我们需要定义一些它们通信的消息。这是一个行为规范。这就定义了客户端和服务器通信的目标、反馈和结果消息:

Goal
为了使用行为完成任务,我们引入了一个目标的概念,它可以通过一个ActionClient发送到一个ActionServer。在移动底盘的情况下,目标将是一个包含关于机器人应该移动到世界何处的信息的、具有固定功能的信息。为了控制倾斜激光扫描仪,目标将包含扫描参数(最小角度,最大角度,速度等)。

Feedback
反馈为服务器实现者提供了一种方式来告诉一个ActionClient关于一个目标的渐进进展。对于移动底盘,这可能是机器人在路径上的当前姿态。为了控制倾斜的激光扫描仪,这可能是在扫描完成之前的时间。

Result
在完成目标后,将结果从ActionServer发送到ActionClient。这与反馈不同,因为它只发送一次。当行动的目的是提供某种信息时,这是非常有用的。对于移动底盘,其结果并不十分重要,但它可能包含机器人的最终姿态。为了控制倾斜的激光扫描仪,结果可能包含从所请求的扫描产生的点云。

.action文件

行为规范使用.action文件。.action文件有目标定义,然后是结果定义,然后是反馈定义,每个部分用3个连字符(---)分隔。

这些文件被放置在包的./action目录,看起来非常类似于服务.srv文件。一个行为规划的摆放可能看起来如下:

./action/DoDishes.action

# 定义目标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

在这个.action的基础上,需要生成6个消息,以便客户端和服务器进行通信。这一代可以在制作过程中自动触发:

使用Catkin创建包

创建包含.action文件的包

find_package(catkin REQUIRED genmsg actionlib_msgs)
add_action_files(DIRECTORY action FILES DoDishes.action)
generate_messages(DEPENDENCIES actionlib_msgs)

额外的, 包含.action文件的包的package.xml必须包含一下以来:

<build_depend>actionlib_msgs</build_depend>
<exec_depend>actionlib_msgs</exec_depend>

创建依赖actionlib API的包

包需要依赖actionlib API来实现一个行为服务器, 或者以来actionlib来使用行为客户端.

CMakeLists.txt

find_package(catkin REQUIRED genmsg actionlib_msgs actionlib)
add_action_files(DIRECTORY action FILES DoDishes.action)
generate_messages(DEPENDENCIES actionlib_msgs)

package.xml

<build_depend>actionlib</build_depend>
<build_depend>actionlib_msgs</build_depend>
<exec_depend>actionlib</exec_depend>
<exec_depend>actionlib_msgs</exec_depend>

结果

对于DoDishes.action,以下消息通过genaction.py生成:

这些消息随后由actionlib内部使用,以在ActionClient和ActionServer之间进行通信。

使用 ActionClient

C++ SimpleActionClient

完整的API参考 C++ SimpleActionClient

快速指南:
假设你已经在chores包里定义了DoDishes.action。下面的代码片段展示了如何发送一个目标到 DoDishes ActionServer,称为"do_dishes"。

   1 #include <chores/DoDishesAction.h> // Note: "Action" is appended
   2 #include <actionlib/client/simple_action_client.h>
   3 
   4 typedef actionlib::SimpleActionClient<chores::DoDishesAction> Client;
   5 
   6 int main(int argc, char** argv)
   7 {
   8   ros::init(argc, argv, "do_dishes_client");
   9   Client client("do_dishes", true); // true -> don't need ros::spin()
  10   client.waitForServer();
  11   chores::DoDishesGoal goal;
  12   // Fill in goal here
  13   client.sendGoal(goal);
  14   client.waitForResult(ros::Duration(5.0));
  15   if (client.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
  16     printf("Yay! The dishes are now clean");
  17   printf("Current State: %s\n", client.getState().toString().c_str());
  18   return 0;
  19 }

注意: 对于C++ SimpleActionClient, 如果一个单独的线程正在为客户机的回调队列服务,waitForServer方法将会工作。使用多线程的spinner运行,或者使用自己的线程来服务ROS回调队列,这需要在客户机的构造函数的spin_thread选项中传递true

Python SimpleActionClient

完整API参考 Python SimpleActionClient

假设你已经在chores包里定义了DoDishes.action。下面的代码片段展示了如何使用python发送一个目标到 DoDishes ActionServer,称为"do_dishes"。

   1 #! /usr/bin/env python
   2 
   3 import roslib
   4 roslib.load_manifest('my_pkg_name')
   5 import rospy
   6 import actionlib
   7 
   8 from chores.msg import DoDishesAction, DoDishesGoal
   9 
  10 if __name__ == '__main__':
  11     rospy.init_node('do_dishes_client')
  12     client = actionlib.SimpleActionClient('do_dishes', DoDishesAction)
  13     client.wait_for_server()
  14 
  15     goal = DoDishesGoal()
  16     # Fill in the goal here
  17     client.send_goal(goal)
  18     client.wait_for_result(rospy.Duration.from_sec(5.0))

实现 ActionServer

C++ SimpleActionServer

完整API参考 C++ SimpleActionServer

快速指南:
假设你已经在chores定义了DoDishes.action。下面的代码片段显示了如何编写一个DoDishes ActionServer,称为"do_dishes"。

   1 #include <chores/DoDishesAction.h>  // Note: "Action" is appended
   2 #include <actionlib/server/simple_action_server.h>
   3 
   4 typedef actionlib::SimpleActionServer<chores::DoDishesAction> Server;
   5 
   6 void execute(const chores::DoDishesGoalConstPtr& goal, Server* as)  // Note: "Action" is not appended to DoDishes here
   7 {
   8   // Do lots of awesome groundbreaking robot stuff here
   9   as->setSucceeded();
  10 }
  11 
  12 int main(int argc, char** argv)
  13 {
  14   ros::init(argc, argv, "do_dishes_server");
  15   ros::NodeHandle n;
  16   Server server(n, "do_dishes", boost::bind(&execute, _1, &server), false);
  17   server.start();
  18   ros::spin();
  19   return 0;
  20 }

Python SimpleActionServer

完整API参考 Python SimpleActionServer

快速指南:
假设你已经在chores定义了DoDishes.action。下面的代码片段显示了如何编写一个DoDishes ActionServer,称为"do_dishes"。

   1 #! /usr/bin/env python
   2 
   3 import roslib
   4 roslib.load_manifest('my_pkg_name')
   5 import rospy
   6 import actionlib
   7 
   8 from chores.msg import DoDishesAction
   9 
  10 class DoDishesServer:
  11   def __init__(self):
  12     self.server = actionlib.SimpleActionServer('do_dishes', DoDishesAction, self.execute, False)
  13     self.server.start()
  14 
  15   def execute(self, goal):
  16     # Do lots of awesome groundbreaking robot stuff here
  17     self.server.set_succeeded()
  18 
  19 
  20 if __name__ == '__main__':
  21   rospy.init_node('do_dishes_server')
  22   server = DoDishesServer()
  23   rospy.spin()

SimpleActionServer 目标策略

在以上ActionServer类中,SimpleActionServer实现了一个单一的目标策略。该政策的说明如下:

调用acceptNewGoal在可用的时候接受一个新的目标。这个目标的状态被设置为在接受时被激活,并且任何先前活动的目标的状态将被设置为抢占。在检查isNewGoalAvailable或调用目标回调和调用acceptNewGoal不会触发preempt回调之间的新目标时接收到的抢占。这意味着,isPreemptRequested应该在接受目标后调用,即使是基于回调的实现,以确保新的目标不会有未决的抢占请求。

教程

参考 Tutorials 页面

报错

<<TracLink(ros-pkg common)>>


2024-02-24 12:28