-
Notifications
You must be signed in to change notification settings - Fork 0
ROS Plan Cheatsheet
<arg name="domain_path"
default="$(find pkg)/pddl/your_pddl_domain.pddl" />
<arg name="problem_path"
default="$(find pkg)/pddl/your_pddl_problem.pddl" />
<arg name="output_problem_path"
default="$(find pkg)/pddl/OUT_your_pddl_problem.pddl" />
<arg name="output"
default="screen" />
<arg name="problem_instance_topic"
default="problem_instance" />
<arg name="planner_out_topic"
default="planner_output" />
<arg name="planner_node_name"
default="node_name" />
<arg name="planner_shell_command"
default="timeout 10 $(find rosplan_planning_system)/common/bin/popf DOMAIN PROBLEM" />
<arg name="data_path"
default="$(find pkg)/data" />
<arg name="planner_node_interface"
default="popf_planner_interface" />
Some remark:
-
problem_instance
is a topic; see the launch file: you can rename it (not suggested)
☝️ notice that the problem reading parsing and loading is performed by the Knowledge Base, and not by the problem interface. The node takes a very particular subversion of PDDL, see the notes.
topics:
/rosplan_knowledge_base/pddl_action_parameters
/rosplan_knowledge_base/status/update
services:
/rosplan_knowledge_base/clear
/rosplan_knowledge_base/domain/functions
/rosplan_knowledge_base/domain/name
/rosplan_knowledge_base/domain/operator_details
/rosplan_knowledge_base/domain/operators
/rosplan_knowledge_base/domain/predicate_details
/rosplan_knowledge_base/domain/predicates
/rosplan_knowledge_base/domain/types
/rosplan_knowledge_base/get_loggers
/rosplan_knowledge_base/query_state
/rosplan_knowledge_base/set_logger_level
/rosplan_knowledge_base/state/functions
/rosplan_knowledge_base/state/goals
/rosplan_knowledge_base/state/instances
/rosplan_knowledge_base/state/metric
/rosplan_knowledge_base/state/propositions
/rosplan_knowledge_base/state/timed_knowledge
/rosplan_knowledge_base/update
/rosplan_knowledge_base/update_array
/rosplan_knowledge_base/update_constraints_oneof
/rosplan_knowledge_base/update_sensed_predicates
Launch file parameters:
<arg name="domain_path"
default="$(find pkg)/pddl/your_pddl_domain.pddl" />
<arg name="problem_path"
default="$(find pkg)/pddl/your_pddl_problem.pddl" />
<arg name="output"
default="screen" />
How to launch the knowledge base:
<!-- knowledge base -->
<node name="rosplan_knowledge_base" pkg="rosplan_knowledge_base" type="knowledgeBase"
respawn="false" output="$(arg output)">
<param name="domain_path" value="$(arg domain_path)" />
<param name="problem_path" value="$(arg problem_path)" />
<param name="use_unknowns" value="false" />
</node>
Remarks:
-
if the parameter
problem_path
is not set, then- the state will contain no objects,
- any propositions will be false,
- and all functions will be initialised to zero.
-
concerning
use_unknowns
,- false : every not stated predicate in the problem file is assumed to be false
- true : every not stated predicate in the problem file is unknown, then they will require explitic statement, otherwise the planner will raise an error.
topics: just one, which transmits the loaded plan.
/rosplan_problem_interface/problem_instance
services:
/rosplan_problem_interface/get_loggers
/rosplan_problem_interface/problem_generation_server
/rosplan_problem_interface/problem_generation_server_params
/rosplan_problem_interface/set_logger_level
Launch file parameters:
<arg name="domain_path"
default="$(find pkg)/pddl/your_pddl_domain.pddl" />
<arg name="problem_path"
default="$(find pkg)/pddl/your_pddl_problem.pddl" />
<arg name="output_problem_path"
default="$(find pkg)/pddl/OUT_your_pddl_problem.pddl" />
<arg name="problem_instance_topic"
default="problem_instance" />
How to launch the Problem Interface:
domain_path
! If given, the component will read the problem from the KB and overwrite the problem file!
☝️ use this component only for publishing a problem out of the topic immediately before planning.
<!-- problem generation -->
<include file="$(find rosplan_planning_system)/launch/includes/problem_interface.launch">
<arg name="knowledge_base" value="rosplan_knowledge_base" />
<!-- <arg name="domain_path" value="$(arg domain_path)" /> -->
<arg name="problem_path" value="$(arg output_problem_path)" />
<arg name="problem_topic" value="$(arg problem_instance_topic)" />
</include>
The launch file just initializes the node problem_interface
. In order to generate the plan, you have to call this service:
rosservice call /rosplan_problem_interface/problem_generation_server
here are some infos about this service:
# rosservice info /rosplan_problem_interface/problem_generation_server
Node: /rosplan_problem_interface
URI: rosrpc://4eb7a141a7c0:46617
Type: std_srvs/Empty
Args:
The service lets you to specify the problem file you want to load. bash command:
rosservice call /rosplan_problem_interface/problem_generation_server_params "problem_path: 'your/problem/path.pddl'
problem_string_response: false"
parameters: (message type: rosplan_dispatch_msgs/ProblemService
)
-
problem_path
: string (the path of the problem file) -
problem_string_response
: bool (???)
here are some infos about this service:
# rosservice info /rosplan_problem_interface/problem_generation_server_params
Node: /rosplan_problem_interface
URI: rosrpc://4eb7a141a7c0:46617
Type: rosplan_dispatch_msgs/ProblemService
Args: problem_path problem_string_response
# rossrv show rosplan_dispatch_msgs/ProblemService
string problem_path
bool problem_string_response
---
bool problem_generated
string problem_string
The problem file is transmitted through the topic /rosplan_problem_interface/problem_instance
. To inspect it via console, here's the command:
rostopic echo /rosplan_problem_interface/problem_instance -n 1 -p
-p
simply prints the output in a more pretty format, nothing special. -n 1
print just one message (each message is the same).
topics: (the node implements an action, because the planner could require a lot of time to find a plan)
# from the include
/rosplan_planner_interface/planner_output
/rosplan_planner_interface/start_planning/cancel
/rosplan_planner_interface/start_planning/feedback
/rosplan_planner_interface/start_planning/goal
/rosplan_planner_interface/start_planning/result
/rosplan_planner_interface/start_planning/status
# from the node (node_name=popf_planning_interface)
/popf_planner_interface/planner_output
/popf_planner_interface/problem_instance
/popf_planner_interface/start_planning/cancel
/popf_planner_interface/start_planning/feedback
/popf_planner_interface/start_planning/goal
/popf_planner_interface/start_planning/result
/popf_planner_interface/start_planning/status
services:
# from the include
/rosplan_planner_interface/planning_server
/rosplan_planner_interface/planning_server_params
# from the node (node_name=popf_planning_interface)
/popf_planner_interface/planning_server
/popf_planner_interface/planning_server_params
Launch file parameters:
<arg name="domain_path"
default="$(find pkg)/pddl/your_pddl_domain.pddl" />
<arg name="problem_path"
default="$(find pkg)/pddl/your_pddl_problem.pddl" />
<arg name="output"
default="screen" />
<arg name="problem_instance_topic"
default="problem_instance" />
<arg name="planner_out_topic"
default="planner_output" />
<arg name="planner_node_name"
default="node_name" />
<arg name="planner_shell_command"
default="timeout 10 $(find rosplan_planning_system)/common/bin/popf DOMAIN PROBLEM" />
<arg name="data_path"
default="$(find pkg)/data/" />
<arg name="planner_node_interface"
default="popf_planner_interface" />
How to launch the component:
<!-- planner interface -->
<include file="$(find rosplan_planning_system)/launch/includes/planner_interface.launch">
<arg name="domain_path" value="$(arg domain_path)" />
<arg name="problem_path" value="$(arg problem_path)" />
<arg name="use_problem_topic" value="true" />
<arg name="problem_topic" value="/rosplan_problem_interface/$(arg problem_instance_topic)" />
<arg name="planner_topic" value="$(arg planner_out_topic)" />
<arg name="data_path" value="$(arg data_path)" />
<arg name="planner_command" value="$(arg planner_shell_command)" />
</include>
<!--
type -> the planner
Planners available:
fd_planner_interface
ff_planner_interface
lpg_planner_interface
metricff_planner_interface
popf_planner_interface
smt_planner_interface
tfd_planner_interface
-->
<node name="$(arg planner_node_name)" pkg="rosplan_planning_system" type="$(arg planner_node_interface)"
respawn="false" output="$(arg output)" />
You can find the executables of the planners in (ROSPlan package folder)/rosplan_planning_system/common/bin/
. They are:
-
popf
- it doesn't support many parts of the ADL specification
-
Metric-FF
-
Contingent-FF
-
PANDA (jar file)
-
prost (probabilistic planning, available in various versions)
each of them should have its interface, hence it is enough to give the name of the interface depending on the planner you're applying, but remember that you shall give a planner_command
calling the planner you want to use.
writing the argument is easy: it's exactly as calling the planner from the console.
-
timeout <time> <cmd>
is a shell utility that executes what specified by the but within seconds. It is useful when the application you're using doesn't support such functionality. For further infos, writetimeout --help
in a shell. -
DOMAIN
is replaced with the domain path file inside the interface - the same replacement happens for
PROBLEM
the components waits for a signal, saying when to start searching the plan.
rosservice call /rosplan_planner_interface/planning_server
The message type is a simple std_msgs/String
.
rostopic echo /rosplan_planner_interface/planner_output -p
topics:
/rosplan_parsing_interface/complete_plan
services:
/rosplan_parsing_interface/parse_plan
/rosplan_parsing_interface/parse_plan_from_file
Launch file parameters:
<arg name="output"
default="screen" />
How to launch the component:
<!-- plan parsing -->
<node name="rosplan_parsing_interface" pkg="rosplan_planning_system" type="pddl_simple_plan_parser"
respawn="false" output="$(arg output)">
<param name="knowledge_base" value="rosplan_knowledge_base" />
<param name="planner_topic" value="/rosplan_planner_interface/planner_output" />
<param name="plan_topic" value="complete_plan" />
</node>
Remarks:
-
planner_topic
-- the input topic -
plan_topic
-- the output of the parsing interface
In order to trigger a plan parsing on a plan already available on the topic from the planner, use this:
rosservice call /rosplan_parsing_interface/parse_plan
# rosservice info /rosplan_parsing_interface/parse_plan
Node: /rosplan_parsing_interface
URI: rosrpc://4eb7a141a7c0:36303
Type: std_srvs/Empty
Args:
Use the service /rosplan_parsing_interface/parse_plan_from_file
as follows:
rosservice call /rosplan_parsing_interface/parse_plan_from_file "plan_path: '[...]/plan_tutorial_03.pddl'"
The parsed plan is an array of fully specified actions.
rostopic echo /rosplan_parsing_interface/complete_plan -n 1
the returned message is similar to this one: (message type: CompletePlan
)
plan:
-
action_id: 0
name: undock
parameters:
-
key: v
value: kenny
-
key: wp
value: wp1
duration: 10.0
dispatch_time: 0.0
-
action_id: 1
name: localise
parameters:
-
key: v
value: kenny
duration: 60.0
dispatch_time: 10.0010004044
Message type:
# rosmsg show rosplan_dispatch_msgs/CompletePlan
rosplan_dispatch_msgs/ActionDispatch[] plan
int32 action_id
string name
diagnostic_msgs/KeyValue[] parameters
string key
string value
float32 duration
float32 dispatch_time
topics:
/rosplan_plan_dispatcher/action_dispatch
/rosplan_plan_dispatcher/action_feedback
/rosplan_plan_dispatcher/dispatch_plan_action/cancel
/rosplan_plan_dispatcher/dispatch_plan_action/feedback
/rosplan_plan_dispatcher/dispatch_plan_action/goal
/rosplan_plan_dispatcher/dispatch_plan_action/result
/rosplan_plan_dispatcher/dispatch_plan_action/status
services:
/rosplan_plan_dispatcher/cancel_dispatch
/rosplan_plan_dispatcher/dispatch_plan
/rosplan_plan_dispatcher/get_loggers
/rosplan_plan_dispatcher/set_logger_level
Launch file parameters:
<arg name="output"
default="screen" />
How to launch the component:
<!-- plan dispatching -->
<node name="rosplan_plan_dispatcher" pkg="rosplan_planning_system" type="pddl_simple_plan_dispatcher"
respawn="false" output="$(arg output)" >
<param name="knowledge_base" value="rosplan_knowledge_base" />
<param name="plan_topic" value="/rosplan_parsing_interface/complete_plan" />
<param name="action_dispatch_topic" value="action_dispatch" />
<param name="action_feedback_topic" value="action_feedback" />
</node>
Remarks:
-
plan_topic
-- the input of the node -
action_dispatch_topic
-- specifies the topic on which the action messages will be published -
action_feedback_topic
-- specifies the topic on the failure or completion of actions will be published
A simulated action is a stub implementation of an action effect, just to test the system.
<include file="$(find rosplan_planning_system)/launch/includes/simulated_action.launch" >
<arg name="pddl_action_name" value="your_action_name" />
</include>
Complete definition:
<include file="$(find rosplan_planning_system)/launch/includes/simulated_action.launch" >
<arg name="pddl_action_name" value="action_man" />
<arg name="action_duration" value="0.0" />
<arg name="action_probability" value="1.0" />
<arg name="knowledge_base" default="rosplan_knowledge_base" />
<arg name="action_dispatch_topic" default="/rosplan_plan_dispatcher/action_dispatch" />
<arg name="action_feedback_topic" default="/rosplan_plan_dispatcher/action_feedback" />
</include>
This launch file contains these XML declarations here:
<?xml version="1.0"?>
<launch>
<!-- arguments -->
<arg name="pddl_action_name" />
<arg name="action_duration" default="0.0" />
<arg name="action_probability" default="1.0" />
<arg name="knowledge_base" default="rosplan_knowledge_base" />
<arg name="action_dispatch_topic" default="/rosplan_plan_dispatcher/action_dispatch" />
<arg name="action_feedback_topic" default="/rosplan_plan_dispatcher/action_feedback" />
<!-- simulated action -->
<node name="rosplan_interface_$(arg pddl_action_name)" pkg="rosplan_planning_system" type="simulatedAction" respawn="false" output="screen">
<param name="knowledge_base" value="$(arg knowledge_base)" />
<param name="pddl_action_name" value="$(arg pddl_action_name)" />
<param name="action_duration" value="$(arg action_duration)" />
<param name="action_probability" value="$(arg action_probability)" />
<param name="action_dispatch_topic" value="$(arg action_dispatch_topic)" />
<param name="action_feedback_topic" value="$(arg action_feedback_topic)" />
</node>
</launch>
☝️ each action effect is a stadalone node.
A action effect is structured as a class with a constructor and a public function concreteCallback
implementing the functionality related to the action to perform.
The header file shall be placed into the folder /include/pkgname
of your package, and implemented into the src
folder, exactly as a library.
Header template: (file actionname.h
)
🔗 header of the father class RPActionInterface
🔗 implementation of the father class RPActionInterface
#include <ros/ros.h>
#include <vector>
#include <unistd.h>
#define ROSPLAN_ACTION_NAME ???actionname???
#include "rosplan_action_interface/RPActionInterface.h"
#include "rosplan_dispatch_msgs/ActionDispatch.h"
/*
#actionDispatch message
int32 action_id
int32 plan_id
string name
diagnostic_msgs/KeyValue[] parameters
float32 duration
float32 dispatch_time
*/
#ifndef KCL_???actionname???
#define KCL_???actionname???
namespace KCL_rosplan {
class RP_???actionname??? : public RPActionInterface
{
public:
/* constructor */
RP_???actionname???( ros::NodeHandle &nh );
/* listen to and process action_dispatch topic */
bool concreteCallback(
const rosplan_dispatch_msgs::ActionDispatch::ConstPtr& msg );
};
}
#endif
Class Definition Template: (file actionname.cpp
)
#include "pkg/actionname.h"
#include "rosplan_dispatch_msgs/ActionDispatch.h"
/*
#actionDispatch message
int32 action_id
int32 plan_id
string name
diagnostic_msgs/KeyValue[] parameters
float32 duration
float32 dispatch_time
*/
namespace KCL_rosplan
{
RP_???actionname???::RP_???actionname???( ros::NodeHandle &nh )
{
// TODO class constructor
}
bool RP_???actionname???::concreteCallback(
const rosplan_dispatch_msgs::ActionDispatch::ConstPtr& msg )
{
// TODO implementation of the action
return true;
}
}
int main(int argc, char **argv)
{
ros::init(argc, argv, ROSPLAN_ACTION_NAME, ros::init_options::AnonymousName);
ros::NodeHandle nh("~");
// create PDDL action publisher
KCL_rosplan::RP_???actionname??? ac( nh );
// run the node
ac.runActionInterface();
return 0;
}
How to launch the action server implementing the aciton:
<node name="rosplan_interface_??actionname???" pkg="???" type="???"
respawn="false" output="screen">
<arg name="pddl_action_name" value="???" />
<arg name="action_duration" value="0.0" />
<arg name="action_probability" value="1.0" />
<arg name="knowledge_base" default="rosplan_knowledge_base" />
<arg name="action_dispatch_topic" default="/rosplan_plan_dispatcher/action_dispatch" />
<arg name="action_feedback_topic" default="/rosplan_plan_dispatcher/action_feedback" />
</node>
empty request, it's just a signal.
blocking service : wait until the plan dispatcher has finished with a outcome that can be true or false.
rosservice call /rosplan_plan_dispatcher/dispatch_plan
type : rosplan_dispatch_msgs/DispatchService
---
bool success
bool goal_achieved