Class PlanSolverBase

Class Documentation

class PlanSolverBase

Abstract base class for plan solvers in PlanSys2.

This class defines the interface for plan solver plugins, including methods for configuration, plan generation, domain validation, and planner execution.

Public Types

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

Public Functions

inline PlanSolverBase()

Default constructor.

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

Configure the plan solver with a lifecycle node and plugin name.

Parameters:
  • lc_node[in] Shared pointer to the lifecycle node.

  • plugin_name[in] The name of the plugin.

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

Generate a plan given a PDDL domain and problem definition.

Parameters:
  • domain[in] The PDDL domain as a string.

  • problem[in] The PDDL problem definition as a string.

  • node_namespace[in] The node namespace (optional).

  • solver_timeout[in] Timeout for the solver (optional, default: 15s).

Returns:

std::optional<plansys2_msgs::msg::Plan> The resulting plan if found, otherwise empty.

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

Validate a PDDL domain.

Parameters:
  • domain[in] The PDDL domain as a string.

  • node_namespace[in] The node namespace (optional).

Returns:

true if the domain is valid, false otherwise.

inline virtual void cancel()

Request cancellation of the current planning process.

virtual bool execute_planner(const std::string &command, const rclcpp::Duration &solver_timeout, const std::string &plan_path)

Execute the planner with a command.

Parameters:
  • command[in] The command to execute the planner.

  • solver_timeout[in] Timeout for the solver.

  • plan_path[in] Path to store the resulting plan.

Returns:

true if the planner executed successfully, false otherwise.

Protected Functions

char **tokenize(const std::string &command)

Tokenize a command string.

Parameters:

command[in] The command string to tokenize.

Returns:

char** Array of C-style strings representing the tokens.

Protected Attributes

rclcpp_lifecycle::LifecycleNode::SharedPtr lc_node_
bool cancel_requested_