README
Problem Expert
The Problem Expert module is responsible for maintaining the instances, predicates and goals of the PDDL problem.
The main class is plansys2::ProblemExpertNode
, which is instantiated from ProblemExpertNode.cpp
. plansys2::ProblemExpertNode
is a rclcpp_lifecycle::LifecycleNode
, but currently the functionality is in the active phase.
The class responsible for maintaining this problem instance is plansys2::ProblemExpert
, which is independent of ROS2.
The Problem Expert is dynamic and volatile, accessing its functionality through ROS2 services. To facilitate the task of the application developer, an plansys2::ProblemExpertClient
class has been implemented that hides the complexity of handling ROS2 messages and services. Its API is similar to that of plansys2::ProblemExpert
, since both have to implement the plansys2::ProblemExpertInterface
interface.
The Problem Expert instantiates a plansys2::DomainExpertClient
, and every update query is verified against domain to check if it is valid.
Every update in the Problem, is notified publishing a std_msgs::msg::Empty
in /problem_expert/update_notify
. It helps other modules and applications to be aware of updates, being not necessary to do polling to check it.
Services
/problem_expert/add_problem_function
[plansys2_msgs::srv::AffectNode
]/problem_expert/add_problem_goal
[plansys2_msgs::srv::AddProblemGoal
]/problem_expert/add_problem_instance
[plansys2_msgs::srv::AffectParam
]/problem_expert/add_problem_predicate
[plansys2_msgs::srv::AffectNode
]/problem_expert/clear_problem_knowledge
[plansys2_msgs::srv::ClearProblemKnowledge
]/problem_expert/exist_problem_function
[plansys2_msgs::srv::ExistNode
]/problem_expert/exist_problem_predicate
[plansys2_msgs::srv::ExistNode
]/problem_expert/get_problem
[plansys2_msgs::srv::GetProblem
]/problem_expert/get_problem_function
[plansys2_msgs::srv::GetNodeDetails
]/problem_expert/get_problem_functions
[plansys2_msgs::srv::GetStates
]/problem_expert/get_problem_goal
[plansys2_msgs::srv::GetProblemGoal
]/problem_expert/get_problem_instance
[plansys2_msgs::srv::GetProblemInstanceDetails
]/problem_expert/get_problem_instances
[plansys2_msgs::srv::GetProblemInstances
]/problem_expert/get_problem_predicate
[plansys2_msgs::srv::GetNodeDetails
]/problem_expert/get_problem_predicates
[plansys2_msgs::srv::GetStates
]/problem_expert/is_problem_goal_satisfied
[plansys2_msgs::srv::IsProblemGoalSatisfied
]/problem_expert/remove_problem_function
[plansys2_msgs::srv::AffectNode
]/problem_expert/remove_problem_goal
[plansys2_msgs::srv::RemoveProblemGoal
]/problem_expert/remove_problem_instance
[plansys2_msgs::srv::AffectParam
]/problem_expert/remove_problem_predicate
[plansys2_msgs::srv::AffectNode
]/problem_expert/update_problem_function
[plansys2_msgs::srv::AffectNode
]
Published topics
/problem_expert/update_notify
[std_msgs::msg::Empty
]