Class SoarAgent

Class Documentation

class SoarAgent

Per-agent wrapper that owns all ROS I/O wiring for one Soar agent.

Returned by SoarRunner::addAgent() as a shared_ptr<SoarAgent>. User code registers interfaces directly on the agent:

auto agent = node->addAgent("MyAgent", path);
agent->addPublisher(std::make_shared<MyPub>(agent->getSmlAgent(), node, "cmd"));
agent->addSubscriber(std::make_shared<MySub>(agent->getSmlAgent(), node, "topic"));

SoarRunner calls updateWorld() on every SoarAgent each decision cycle via the smlEVENT_AFTER_ALL_OUTPUT_PHASES callback.

Public Functions

inline SoarAgent(sml::Agent *pAgent, rclcpp::Node::SharedPtr node)
Parameters:
  • pAgent – Raw sml::Agent owned by the kernel (non-owning).

  • node – Shared ptr to SoarRunner (creates ROS primitives).

SoarAgent(const SoarAgent&) = delete
SoarAgent &operator=(const SoarAgent&) = delete
inline sml::Agent *getSmlAgent() const

Raw sml::Agent pointer (lifetime managed by the Soar kernel).

inline rclcpp::Node::SharedPtr getNode() const

The ROS node this agent is attached to.

template<typename T>
inline bool addPublisher(std::shared_ptr<Publisher<T>> output)

Register a Publisher; topic name is used as the Soar command name.

template<typename T>
inline bool addPublisher(std::shared_ptr<Publisher<T>> output, const std::string &commandName)

Register a Publisher with an explicit Soar output-link command name.

template<typename T>
inline bool addSubscriber(std::shared_ptr<Subscriber<T>> input)

Register a Subscriber.

template<typename T>
inline bool addService(std::shared_ptr<Service<T>> service)

Register a Service; service name is used as the Soar command name.

template<typename T>
inline bool addService(std::shared_ptr<Service<T>> service, const std::string &commandName)

Register a Service with an explicit Soar command name.

template<typename T>
inline bool addClient(std::shared_ptr<Client<T>> client)

Register a Client; client name is used as the Soar command name.

template<typename T>
inline bool addClient(std::shared_ptr<Client<T>> client, const std::string &commandName)

Register a Client with an explicit Soar command name.

template<typename T>
inline bool addActionClient(std::shared_ptr<ActionClient<T>> action_client)

Register an ActionClient; action name is used as the command name.

template<typename T>
inline bool addActionClient(std::shared_ptr<ActionClient<T>> action_client, const std::string &commandName)

Register an ActionClient with an explicit Soar command name.

inline void updateWorld()

Process output-link commands then flush all input queues. Called by SoarRunner::updateWorld() every decision cycle.