[Documentation] [TitleIndex] [WordIndex

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:

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

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

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.

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

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

GoalHandle

Returns the goal associated with the handle

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

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

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

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

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

Registering Feedback Topics

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

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.

Present at review:

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:

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

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

Stu:

Roland:

Conor:

Meeting agenda

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

Notes

Conclusion

Notes 2009-07-21

action specification



2024-02-24 12:24