[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.

概要

様々なROSベースのシステムにおいて、何らかのタスクをnodeにリクエストとして送り、そのリクエストの返事を受け取りたい場合が起こります。これは、今のところROS servicesを通じて実現されています。

しかし場合によっては、serviceの実行に時間がかかる時、ユーザが実行中にキャンセルしたり、リクエストの進行状況を定期的に知りたい時があります。actionlibのパッケージは、ゴールまで長い行程のかかるものの中断可能なサーバプログラムを作成するツールを提供します。作成したサーバにリクエストを送るため、クライアントが使うインターフェースも同様に提供します。

詳細な説明

actlionlibが「ボンネットの中」をどのように動かしているかについての十分な議論については、Detailed Descriptionをご覧ください。

クライアントサーバ インタラクション

ActionClientActionServer は、ROSメッセージ上に構築された "ROS Action Protocol" に従って通信を行います。クライアントとサーバは、「ゴールの要求」(クライアント側)と「ゴールの実行」(サーバ側)を行うための、シンプルなAPIをユーザに提供することになります。これらの要求と実装は、それぞれファクションコールとコールバックを通じて行われます。

client_server_interaction.png

Action Specification: Goal, Feedback, Result

クライアントとサーバがやり取りするには、幾つかのメッセージを定義する必要があります。これは action specification (アクション仕様書)で行われており、この中でクライアントとサーバがやり取りするgoal、feedback、resultのメッセージが定義されています。それぞれについて説明します。

Goal(ゴール)
アクションを使ってタスクを完了させるために、「ゴールの概念」を ActionClient から ActionServer に送ることができるようにしたものです。例えば台車の移動の場合、goalは PoseStamped メッセージということになるでしょう。このメッセージは、ロボットが行くべき世界座標系での地点の情報を持ちます。チルトレーザスキャナを制御するという場合なら、goalにはスキャンするときのパラメータ(最小角、最大角、スピード等)が含まれるでしょう。

Feedback(フィードバック)
feedbackは、goalへの進捗状況について、サーバ側が ActionClient に伝える手段を提供します。移動台車の場合はゴールへのパス内での現在の姿勢ということになるでしょう。チルトレーザスキャナの場合はスキャンが終わるまでの残り時間ということになるでしょうか。

Result(リザルト)
resultはgoalが達成された時、 ActionServer から ActionClient に送られます。これは1回しか送られないという意味で、feedbackとは違うものです。アクションの目的が、何らかの情報取得の場合にはresultはとても便利です。移動台車の場合はresultはそんなに便利なものでなく、単にロボットの最終的な姿勢がresultに含まれることぐらいしか考えられません。しかしチルトレーザスキャナの場合、resultにはスキャナで得られたポイントクラウドが含まれることでしょう。

.action ファイル

action specification の定義には .action ファイルが用いられます。 .action ファイルにはgoalの定義が記述され、その後にreasultの定義、feedbackの定義がこの順に記述されます。これら各定義の間は3つのハイフン(---)で区切られます。

これらのファイルは、パッケージの ./action ディレクトリに置かれます。サービスの .srv ファイルの場合とよく似ています。例えば皿洗いを行うためのaction specificationは次のようになるでしょう:

./action/DoDishes.action

# Define the 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つのメッセージの生成が必要になります。makeの過程で自動実行されます。以下にそのための手順を示します。

Catkin

あなたのCMakeLists.txtで、catkin_package() の "前" に、次のように記述します。

find_package(catkin REQUIRED genmsg actionlib_msgs)
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>
<run_depend>actionlib</run_depend>
<run_depend>actionlib_msgs</run_depend>

Rosbuild

catkin でなく rosbuild を使っている場合、 rosbuild_init() の "前" に次のように記述します。

rosbuild_find_ros_package(actionlib_msgs)
include(${actionlib_msgs_PACKAGE_PATH}/cmake/actionbuild.cmake)
genaction()
rosbuild_genmsg()

1.0シリーズ(boxturtle)の場合は次のように書きます。

rosbuild_find_ros_package(actionlib)
include(${actionlib_PACKAGE_PATH}/cmake/actionbuild.cmake)
genaction()
rosbuild_genmsg()

加えて、パッケージの manifest.xml には次のように依存関係を含めないといけません。

<depend package="actionlib"/>
<depend package="actionlib_msgs"/>

Results

DoDishes.actionのために、genaction.pyによって次のメッセージが生成されます。

これらのメッセージは、 ActionClient と ActionServer 間の通信のために、 actionlib によって内部的に用いられます。

ActionClient の利用

C++ SimpleActionClient

APIリファレンス: C++ SimpleActionClient

クイックスタート:
chores (日々の雑用)パッケージの中で、あなたが DoDishes.action を定義した状況を考えましょう。次のスニペットは、どうやってゴールを "do_dishes"と名前の付いた DoDishes アクションサーバに送るかを示しています。

   1 #include <chores/DoDishesAction.h>
   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 メソッドが機能します。そのためには、クライアントのコンストラクタの spin_thread オプションを true にする、マルチスレッドのスピナーを走らせる、あるいはROSのcall backキューを提供するスレッドを実装して使うことが必要です。

Python SimpleActionClient

APIリファレンス: Python SimpleActionClient

chores (日々の雑用)パッケージの中に、 DoDishes.action が存在する場合を考えましょう。次のスニペットは、Pythonでどうやってゴールを "do_dishes"と名前の付いた DoDishes アクションサーバに送るかを示しています。

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

ActionServerの実装

C++ SimpleActionServer

API リファレンス: C++ SimpleActionServer

クイックスタート:

chores (日々の雑用)パッケージの中で、 DoDishes.action を定義した場合を考えましょう。次のスニペットは、どのように "do_dishes" という名前の付いた DoDishes アクションサーバを書くかを示しています。

   1 #include <chores/DoDishesAction.h>
   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)
   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

クイックスタート:
Pythonの場合は次のようになります。

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

SimpleActionServer Goal Policies

SimpleActionServer では ActionServer クラスの冒頭にあるゴールポリシー(goalを操作するための方策)が実装されています。この実装の仕様は次のようなものです。

acceptNewGoal を呼ぶと、新しいgoalが使える時にそのgoalが受理されます。そのgoalの状態は許可によってアクティブになり、他のgoalの状態はプリエンプト(中断)にセットされます。 isNewGoalAvailable がチェックされている間、あるいは新しいgoalのコールバックが起動して acceptNewGoal が呼ばれている間、新しいゴールが中断要求を受けても、中断のコールバックは起動しません。これの意味するところは、 たとえ実装がコールバックに基づいていても、新しいgoalが未処理の中断の要求を受けていないことを保証するために、新しいgoalが受理された後には isPreemptRequested がチェックされるべきだということです。

Tutorials

Tutorials を参照のこと。

Report a Bug

<<TracLink(ros-pkg common)>>


2022-05-28 12:40