API review

Proposer: Eitan Marder-Eppstein and Vijay Pradeep

Overview and Goals

The action_tools package is meant to assist ROS users in writing nodes that accomplish specific tasks. Examples of this include: moving the base to a target location, taking a laser scan with parameters that are passed in and returning the resulting point cloud, detecting the handle of a door, etc. To accomplish these tasks, we introduce the notion of a goal that can be sent to an action server by an action client. In the case of moving the base, the goal would be a PoseStamped message that contains information about where the robot should move to in the world. Each goal sent to an action server has an associated status. The values for the status of a goal are as follows:

  • PENDING - The goal has yet to be processed by the action server
  • ACTIVE - The goal is currently being processed by the action server
  • SUCCEEDED - The goal was achieved successfully by the action server
  • ABORTED - The goal was aborted by the action server
  • PREEMPTED - The goal was preempted by either another goal, or a preempt message being sent to the action server
  • LOST - The goal was sent by the ActionClient, but disappeared due to some communication error

Action Specification

To reason about the individual goals, each message is tagged with a GoalID going over ROS. To facilitate this (and hide the implementation from the end user), we are defining an action specification, from which we can autogenerate the necessary .msg files.

Here is an example action specification:

MoveBase.action

#goal definition
robot_msgs/PoseStamped goal
---
#result definition
robot_msgs/PoseStamped result

---
#names the message generated for this feedback channel CurrentPosition
robot/msgs/PoseStamped current_position

#names the message generated for this feedback channel WaypointLabel
std_msgs/String waypoint_label

Action Server

The constructor takes a name, a frequency with which to publish status messages for each goal, and a NodeHandle to operate in

  • ActionServer(ros::NodeHandle node, string name, double status_freqauency)

Used in polling implementations of an action, returns true if a new goal is available, false otherwise

  • bool isNewGoalAvailable()

Used to accept the next available goal for the action. Upon acceptance, the previous goal (if one was active) will have its status set to preempted and the new goal will have its status set to active.

  • GoalHandle acceptNextGoal()

Used in polling implementations of an action server, returns true if a preempt of the current goal has been requested, false otherwise

  • bool isPreemptRequested()

Returns true if the action server has a goal in an active state, false otherwise

  • bool isActive()

GoalHandle

Returns the goal associated with the handle

  • boost::shared_ptr<const Goal> getGoal()

Will set the status of the goal to succeeded. Optionally, a result can be sent to the client on success as well.

  • void succeeded()

  • void succeeded(Result r)

Will set the status of the goal to aborted. Optionally, a result can be sent to the client on abort as well.

  • void aborted()

  • void aborted(Result r)

Will set the status of the goal to preempted. Optionally, a result can be sent to the client on preempt as well.

  • void preempted()

  • void preempted(Result r)

Allows the user of an action server to register a callback that is invoked on reception of a new goal

  • void registerGoalCallback(boost::function<void ()> cb)

Allows the user of an action server to register a callback that is invoked on reception of a preempt request

  • void registerPreemptCallback(boost::function<void ()> cb)

Registering Feedback Topics

  • Feedback from an action server has a goal id associated with it. Thus, the client only receives feedback about their active goal
  • FeedbackPublisher pub = as.registerFeedback(topic);

Simple Action Server Example

void updateLoop(double freq){
  ros::NodeHandle n;
  MoveBaseActionServer as(n, "move_base", 0.5);
  GoalHandle goal_handle;
  ros::Publisher pub = n.advertise<robot_msgs::PoseStamped>("~current_goal", 1);
  as.registerGoalCallback(boost::bind(&goalCB, _1));
  as.registerPreemptCallback(boost::bind(&preemptCB));
  ros::Rate r(freq);
  while(n.ok()){
    r.sleep();
    if(as.isActive()){
      if(!as.isPreemptRequested()){
        if(as.isNewGoalAvailable()){
          ROS_INFO("This action has received a new goal");
          goal_handle = as.acceptNextGoal();
        }
        boost::shared_ptr<const robot_msgs::PoseStamped> goal = goal_handle.getGoal();
        if(goal->pose.position.x > 100.0){
          ROS_INFO("This action aborted");
          as.reportAbort();
          continue;
        }
        if(goal->pose.position.y > 100.0){
          ROS_INFO("This action succeeded");
          as.reportSuccess();
          continue;
        }
        pub.publish(*goal);
      }
      else {
        ROS_INFO("This action has been preempted");
        as.reportPreempt();
      }
    }
    else if(as.isNewGoalAvailable()){
      ROS_INFO("This action has received a new goal");
      goal_handle = as.acceptNextGoal();
    }
  }
}

Action Client

Constructing an ActionClient
Constructor for the ActionClient takes a name and a node handle. Optionally, takes arguments on whether or not to expect a result from the action server and how long to wait on reception of status messages from the server before timing out. The combination of the NodeHandle & name define the namespace in which the ActionServer and ActionClient communicate.

    ActionClient(ros::NodeHandle node, string name,
                 bool expecting_result = false,
                 ros::Duration server_status_timeout = 5sec)

Sending Goals to the ActionServer
Uses the client to send a goal to the action server. Allows the user to specify a callback that gets called when the status of the goal transitions to a terminal state. Also, allows the user to specify values for timeouts that can occur during execution of a goal and their associated callbacks.

    GoalHandle sendGoal(const Goal& goal,
                        CompletionCallback completion_callback          = CompletionCallback(),
                        ActiveCallback active_callback                  = ActiveCallback(),
                        const ros::Duration& runtime_timeout            = ros::Duration(0,0),
                        AckTimeoutCallback ack_timeout_callback         = AckTimeoutCallback(),
                        PreemptTimeoutCallback preempt_timeout_callback = PreemptTimeoutCallback(),
                        const ros::Duration& ack_timeout                = ros::Duration(5,0),
                        const ros::Duration& wait_for_preempted_timeout = ros::Duration(5,0),
                        const ros::Duration& comm_sync_timeout          = ros::Duration(5,0))

  ros::NodeHandle n;
  MoveBaseClient ac(n, "move_base", false);
  // Send a goal without a result callback
  GoalHandle gh = ac.sendGoal(goal_pose);
  // Send a goal with a result callback
  GoalHandle gh = ac.sendGoal(goal_pose, &callback);
  // Send a goal with all the options
  GoalHandle gh = ac.execute(goal_pose, &callback, runtime_timeout, &ackTimeoutCb, &preemptTimeoutCb, ack_timeout, preempt_timeout);

Preempting/Recalling Goals
We need to decide on which of these preemption mechanisms we want to implement

  • preemptGoal(const GoalHandle&) - Preempt a specific goal

  • preemptAllGoals(ros::Time) - Preempt all goals dispatched before a given time

  • preemptAllLocalGoals() - Preempt all goals dispatched from this ActionClient

Polling API
Lets the user query the ActionClient to get information about the progress of the current goal. All of these methods require the user to pass in a GoalHandle, so that the ActionClient knows which goal the user is asking about.

  • bool isGoalFinished(const GoalHandle&)

  • GoalStatus getGoalStatus(const GoalHandle&)

  • boost::shared_ptr<const Result> getGoalResult(const GoalHandle&)

  • GoalStatus waitUntilFinished(const GoalHandle&)

Present at review:

  • List reviewers

Question / concerns / comments

Enter your thoughts on the API and any questions / concerns you have here. Please sign your name. Anything you want to address in the API review should be marked down here before the start of the meeting.

Bhaskara:

  • syntax for feedback in action definition makes it look like PoseStamped and CurrentPosition are different types of feedback. Maybe something like feedback/current_position: PoseStamped?

  • What happens on an action client timeout?
  • Action client should also provide a blocking call
  • If I want to preempt all active and pending goals with a new one, how do I guarantee this from the client side?
    • [Vijay] I added some potential preemption mechanisms. Hopefully one of these fits your needs.

Alex Sorokin: I have a few desired features to the action interface:

  • Explicit active time interval representation. I'd like to know the time span when an action has been working on the current goal.
    • [Vijay] This can easily be added as a custom field in some specific action's Result msg. However, if this is a pervasive enough use case, then it could be autogenerated as part of the result message, and computed automatically for every action.
  • Support for multiple goals. I can have a simple action to annotate an image, but it doesn't work for multiple images. Currently new image would preempt the previous one. Ideally, I'd like to have a list of active goals and completions to be reported when any image has been labeled.
    • [Vijay] We tried to design the API to support multiple goals, even though this isn't implemented yet. Once we support multiple goals, nothing should need to change on the client side.

Alex Sorokin: Other features for the action framework that aren't directly the action interface:

  • Recording action state for all actions. I'd like to record the state transitions for all actions, so that I can access it later. Right now that requires (1) knowing the action feedback topic names and (2) recording all feedback messages.
  • Querying for time intervals when the action was active. I'd like to query a service with an action name and get the intervals when the action succeeded (or when the action failed).

Stu:

  • sendGoal takes too many options.

    • Put the timeouts into the constructor for ActionClient.

    • Change the error callbacks somehow:
      • Combine them all into a single error_callback
      • Have the completion_callback take the status, and allow the status to be an error. Is there any use case where the user would call sendGoal without an error callback?
  • The syntax for the action specification seems...odd. Can you make it look more like a ROS service specification?
    • [Eitan] Changed to look more like services. We can iterate on this more though at the meeting.

Roland:

  • Is it really necessary to always publish a "pulse" of status messages while running? In many cases (I think), people will just be interested in the state transitions.

Conor:

  • General concerns:
    • A big change to the action api. Can u provide an automatic upgrade by wrapping robot_actions?
      • [Eitan] We could wrap robot_actions, but rather than put a lot of work into making sure the old and new actions play nice, I think I'd like to branch and work on porting all the actions to the new API. Just my opinion on it.
    • Not obvious to me at least that it is making things easier for users. Seems more complex
      • [Eitan] I guess I can only say that I disagree. The old actions were confusing to use/debug for me personally and lacked the flexibility I needed to write reasonably sophisticated actions. What exactly do you find overly complex? That would help focus discussion on this point.
    • Requiring users to write the update loop code as shown seems like it opens the implementation up to more error and is more work.
      • [Eitan] To me, the update loop is a design decision that belongs to the user of the action API. With a ros::Rate object, its really easy to write (4 lines of code) and, unlike the old actions, it allows the user to run the loop at whatever rate they wish. The old implementation just slept for 0.01 seconds every cycle, which for me just added to my overall confusion. Also, some action servers may choose to forgo an update loop completely in favor of a callback-based implementation. Oh... and not making the update loop explicit allows the user to have the option of a single threaded implementation of an action rather than forcing an extra thread on them to handle the runLoop as the old actions did.
    • These comments can be evaluated more concretely by evaluating a port from one API to another. Can we look at the code for doing that to decide?
      • [Eitan] I've ported move_base and still have the old code around... we should go through it.
    • Will you take on upgrading everyone and verifying that M2 still works?
      • [Eitan] I care enough about this to take on this responsibility. However, things will go faster if other's are willing to chip in. If the original action implementers aren't willing to help switch to the new API... myself or someone I recruit will do it for them.
  • Where is the callback to catch the transition to the active state?
    • [Eitan] Ooops. It was supposed to be there but definitely isn't. We'll add a callback for this to the sendGoal method. Good catch... our bad.
  • Is the action client a templated class? If we want compile time type checking it should be.
    • [Eitan] Yes, the action client and the action server are both templated classes
  • I assume you plan to deprecate the robot_actions package. Over what time frame had you this in mind?
    • [Eitan] To me, a pre-requisite for completing Milestone 3 is having everything ported to the new API. To me, this is important enough to push back the completion date of M3, ideally this won't happen... but I really feel that we need to get actions right before release because a lot of people are going to use them.

Meeting agenda

To be filled out by proposer based on comments gathered during API review period

Notes

  • heartbeat vs just transition messages: should be hidden from user, timeout parameter discussion will be taken offline
  • state is stored on the server, not the client (except LOST state)
  • multiple goals: for the moment, just one goal at a time (multiple goals makes the semantics much harder to generalize)
    • example of multiple goals in parallel: annotate a stream of images
    • example of serial multiple goals: queue of waypoints
    • first get the single-goal case "done right" though
    • should start passing goal handles into callbacks to prepare supporting multiple goals
    • {X} beware possible can of worms: maybe just concentrate on single goal actions here, do more fancy stuff later elsewhere

  • action definition files: essentially a service with two kinds of replies
    • input: goal (one message type)
    • output 1: feedback (zero or more message types)
    • output 2: final result (zero or one message type)
    • connection header idea (discussion moved offline, Ken, Brian, ...)
    • would be nice to have an "action header" or so, e.g. for compile-time checking (Wim and Conor, moved offline)
  • what goes into "feedback"? lightweight stuff... bigger things (e.g. annotated images) go into final result.
  • other ideas:
    • move some of the methods onto a goal handle object?
    • policy objects for multiple goals handling, exception handling (e.g. is it an error to call succeed() twice or just ignore that?)
  • /!\ client side, i.e. sendGoal()

    • completion callback specified each time or once at setup?
    • specify callbacks using boost::bind or so to enable passing user data into them?
    • make sure LOST state means the client will not receive any more data from that action, even if it continues to live in the server... another potential can of worms if we are trying to be too intelligent about it (discussion about heartbeat from client back to server etc).

Conclusion

  • /!\ decide whether (and where) we want (to expose) goal handles or not in this implementation

    • [Eitan] I think that goal handles are important even in the single goal case because they expose hidden state within the action server. For example, if we decide to call accept, preempt, succeed on a goal handle, the user is guaranteed that the status will change for the intended goal. However, if the user just has a message around and they call succeed on the action server, they may not be succeeding on the goal that they think they are. This is, of course, a bug on the user's side, but one that is hard to track down. For example, if the user stores the old goal for some reason and accidentally decides to process it twice, it'll be hard to tell because they'll report success on the new goal even though it has never been processed. With the goal handles, however, they would see that the status on the new goal did not change when they expected it to. Just a thought.
      • remain wire-compatible with older protocol?
  • rediscuss later (over time)

Notes 2009-07-21

action specification

  • use implicitly typed data definition based on order
    • goal then result then feedback
    • Allow composite types for all three
  • simplify to one feedback type for now
  • require two delimiters
  • this is sort of a start for interfaces
    • it has some state associated with the goal
    • this is not close enough to be a blocker
    • a state machine in the node would be
    • actions can be more of a primative building toward interfaces
  • if going with goal handle the class should have hooks to show that it is using a policy SINGLE_GOAL_PREMPT_ON_NEW_GOAL
  • a node handle should report a failure if it goes out of scope (this is different than aborted, maybe should recover REJECTED)
  • we're leaning toward providing the server which requires the user to implement policy
  • could do a single policy class, but it ultimately up to the user to make sure of good policy
    • how much can we enforce that if a preemt came in, should we enforce that this is prempted? We cannot avoid all race conditions.
    • should the policy be implemented on the client or the server?
    • should we make all interactions follow this? why shouldn't we make base controller in velocity mode use this? what time scale do we expect to work?


Wiki: actionlib/Reviews/2009-07-20_API_Review (last edited 2009-08-14 20:52:18 by localhost)