Class SoarRunner

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class SoarRunner : public rclcpp::Node

ROS2 node that manages a Soar kernel and its agents.

Responsibilities:

  • Own the sml::Kernel and the spin thread.

  • Create sml::Agent instances on request and wrap them in SoarAgent.

  • Expose ROS2 service interfaces to start/stop the kernel and launch the Soar Java debugger.

I/O wiring is done on each SoarAgent returned from addAgent(), not here.

Public Functions

explicit SoarRunner(const std::string &node_name)
~SoarRunner()
std::shared_ptr<SoarAgent> addAgent(const std::string &agent_name, const std::string &source_file)

Create a new Soar agent and return a handle for I/O wiring.

Parameters:
  • agent_name – Name passed to sml::Kernel::CreateAgent().

  • source_file – Path to the .soar file to load. Empty = no load.

Returns:

Per-agent handle; call add*() methods on it.

void run()

Start the Soar decision-cycle thread.

inline void startThread()

Start the Soar decision-cycle thread (alias for run()).

inline void stopThread()

Stop and join the Soar decision-cycle thread.

inline void updateWorld()

Process all agents’ I/O. Called via updateEventHandler every decision cycle (smlEVENT_AFTER_ALL_OUTPUT_PHASES).

void debuggerLaunch(const std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<std_srvs::srv::Trigger::Request> request, std::shared_ptr<std_srvs::srv::Trigger::Response> response)

/soar_ros/debugger/launch — stop the kernel thread and spawn the Soar Java debugger for all agents.

void getSoarKernelStatus(const std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<std_srvs::srv::Trigger::Request> request, std::shared_ptr<std_srvs::srv::Trigger::Response> response)

/soar_ros/kernel/status — report whether the kernel thread is currently running.

void runSoarKernel(const std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<std_srvs::srv::Trigger::Request> request, std::shared_ptr<std_srvs::srv::Trigger::Response> response)

/soar_ros/kernel/run — start the kernel thread via ROS.

void stopSoarKernel(const std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<std_srvs::srv::Trigger::Request> request, std::shared_ptr<std_srvs::srv::Trigger::Response> response)

/soar_ros/kernel/stop — stop the kernel thread via ROS.