Skip to content

ROSplan dispatch notes

Francesco Ganci edited this page Jul 5, 2022 · 2 revisions

Notes about ROSplan Dispatcher

Schematic

176646320-655c6d57-f3ef-4901-a704-cccc8b9f6733

Structure of an action

A custom action is simply a node

  • subscribed to /rosplan_plan_dispatcher/action_dispatch (type rosplan_dispatch_msgs/ActionDispatch)
  • publishing on /rosplan_plan_dispatcher/action_feedback (type rosplan_dispatch_msgs/ActionFeedback)

Moreover it can access to the Knowledge Base in order to simulate the action also at a logical level.

1 -- How to trigger an action

An action node is triggered when it receives a message from /rosplan_plan_dispatcher/action_feedback, and the name of the action is the same the node is implementing. The dispatcher simply publishes a message, letting the nodes to manage which one should accomplish the request.

Message rosplan_dispatch_msgs/ActionDispatch

message structure:

int32 action_id
int32 plan_id
string name
diagnostic_msgs/KeyValue[] parameters
float32 duration
float32 dispatch_time

An example of message from the topic: it corresponds to a PDDL action instance such as (dock kenny wp0) to be executed.

action_id: 7
plan_id: 0
name: "dock"
parameters: 
  - 
    key: "v"
    value: "kenny"
  - 
    key: "wp"
    value: "wp0"
duration: 30.0
dispatch_time: 370.0069885253906

Typical Node Working Cycle

if you implement the action node with the class RPActionInterface, the node cycle is quite similar to the one shown in this pseudocode:

IF action name matches THEN:
  check action for malformed parameters
  update knowledge base (at start effects)
  publish feedback (action enabled)
  success = concreteCallback()
  IF success THEN:
      update knowledge base (at end effects)
      publish feedback (action achieved)
  ELSE
      publish feedback (action failed)
  RETURN success

Using that class, you have to implement only the method concreteCallback(), allowing the system to update the knowledge in the way specified in the PDDL file.

Sometimes you don't want this kind of behaviour. Sometimes you should know exactly how to update the knowledge base, and sometimes you just want to use the knowledge base as a simple database for the actions, hence you maybe want to define and use predicated different from the ones in the PDDL file. In these cases, the pseudocode shown above is still valid, but you should reimplement also the other parts, hence the entire class.

How to deal with failures and success

Each action communicates the outcome through action_feedback. The code is similar to this ne in C++:

// publish feedback (achieved)
fb.status = rosplan_dispatch_msgs::ActionFeedback::ACTION_SUCCEEDED_TO_GOAL_STATE;
action_feedback_pub.publish(fb);

// publish feedback (failed)
fb.status = rosplan_dispatch_msgs::ActionFeedback::ACTION_FAILED;
action_feedback_pub.publish(fb);

how many feedback for a node? one feedback at the beginning of the node, and one at the end saying the outcome of the action.

how to understand which node took took the action? the node in charge to execute the action is the only one which sends something through the action_feedback topic. In particular, the first message to be sent is rosplan_dispatch_msgs::ActionFeedback::ACTION_DISPATCHED_TO_GOAL_STATE for classical planning, and rosplan_dispatch_msgs::ActionFeedback::ACTION_DISPATCHED_TO_START_STATE for the temporal planning.

Feedback message

message structure:

int32 ACTION_PRECONDITION_FALSE = 0
int32 ACTION_ENABLED = 1
int32 ACTION_DISPATCHED_TO_GOAL_STATE = 1
int32 ACTION_SUCCEEDED_TO_GOAL_STATE = 2
int32 ACTION_DISPATCHED_TO_START_STATE = 3
int32 ACTION_SUCCEEDED_TO_START_STATE = 4
int32 ACTION_FAILED = 10

int32 action_id
int32 plan_id
int32 status
diagnostic_msgs/KeyValue[] information

Note that, if ACTION_PRECONDITION_FALSE is sent, it means that there's something unexpected occurred in executing the plan!

Implementation Templates

Standard Implementation

see this link

Non-standard implementation

In case you don't want to use the standard implementation of the node, here's a minimal template of ROSPlan action.

Header file:

class file:

ROS node: