Class PlanSolverBase

Class Documentation

class PlanSolverBase

Public Types

using Ptr = std::shared_ptr<plansys2::PlanSolverBase>

Public Functions

inline PlanSolverBase()
inline virtual void configure(rclcpp_lifecycle::LifecycleNode::SharedPtr lc_node, const std::string &plugin_name)

Configures the plan solver lifecycle node.

Parameters:
  • lc_node – Shared pointer to the lifecycle node.

  • plugin_name – The plugin name.

virtual std::optional<plansys2_msgs::msg::Plan> getPlan(const std::string &domain, const std::string &problem, const std::string &node_namespace = "", const rclcpp::Duration solver_timeout = 15s) = 0

Returns a plan given a PDDL domain and problem definition.

Parameters:
  • domain – The PDDL domain as a string.

  • problem – The PDDL problem definition as a string.

  • node_namespace – The node namespace.

Returns:

An optional containing the resulting plan, if one was found.

virtual bool isDomainValid(const std::string &domain, const std::string &node_namespace = "") = 0

Exposes a capability to validate a PDDL domain.

Parameters:
  • domain – The PDDL domain as a string.

  • node_namespace – The node namespace.

Returns:

True if the domain is valid, otherwise false.