Class SoarRunner
- Defined in File SoarRunner.hpp 
Inheritance Relationships
Base Type
- public rclcpp::Node
Class Documentation
- 
class SoarRunner : public rclcpp::Node
- Singelton class to manage the Soar kernel thread, main ROS interface to run/ stop the kernel and to attach interfaces via a builder pattern, e.g. soar_ros::Publisher(), soar_ros::Subscriber(), soar_ros::Service() and soar_ros::Client(). - Public Functions - 
SoarRunner(const std::string &agent_name, const std::string &path_productions)
- Instantiates the Soar kernel and generates ROS2 interfaces. Further setup in SoarRunner::addAgent() for first agent. - Parameters:
- agent_name – The agents name. 
- path_productions – Filepath to main *.soar file relative to the package root. 
 
- Throws:
- std::runtime_error – on sml::Kernel setup error. 
 
 - Enable external control to start the debugger and stop the run thread via. - std_srvs:interfaces/srv/Trigger/// via - /soar_ros/debugger/launch- The run thread is stopped automatically since the debugger is not responsive if the thread is running. Reason to be investigated. The thread running the Soar kernel is not automatically restarted once the debugger was closed. Manually restart the thread via the provided SoarRunner::runSoarKernel() interface. @note Launching the Soar debugger without the command requires stopping the kernel via SoarRunner::stopSoarKernel() related topic. Otherwise, the debugger will remain frozen/ unresponsive. @param request_header @param request @param response 
 - ROS2 interface to get current Soar kernel status (run/ stop) via. - std_srvs:interfaces/srv/Trigger/// via - /soar_ros/kernel/status- @param request_header Unused. @param request Empty. @param response "Soar Kernel isRunning: true" if running, otherwise "Soarkernel isRunning: false". @warning This does not catch the state of the Soar kernel correctly, once the kernel is started/ stopped via the Soar debugger! 
 - ROS2 Service interface to stop Soar kernel if it is currently running via. - std_srvs:interfaces/srv/Trigger/// via - /soar_ros/kernel/run- @param request_header Unused. @param request Empty. @param response "Soar kernel isRunning: true" if started succesfully, otherwise "Soar kernel isRunning: false". 
 - ROS2 Service interface to start (run) Soar kernel if it is currenlty stopped. - std_srvs:interfaces/srv/Trigger/// via - /soar_ros/kernel/stop- @param request_header @param request Empty. @param response "Soar Kernel isRunning: false" if stopped succesfully, otherwise "Soarkernel isRunning: true". 
 - 
sml::Agent *addAgent(const std::string &agent_name, const std::string &path_productions)
- Add a new Soar agent and register callbacks related to ROS. - Warning - Handling multiple agents in one SoarRunner instance is not implemented yet! - Warning - The path might depend on the install location specified in cmake sctipts - Parameters:
- agent_name – The agents name 
- path_productions – Path to the Soar source files. 
 
- Throws:
- std::runtime_error – on sml::Agent::loadProductions() error. 
- Returns:
 
 - 
~SoarRunner()
- Stops the Kernel thread and wait until joined, closes Soar Debugger in debug mode. 
 - 
inline sml::Agent *getAgent()
 - Adds a soar_ros::Publisher() to the SoarRunner. - The output command is assumed to be the topic name of the Publisher. - Template Parameters:
- T – ROS2 message type 
- Parameters:
- output – 
- Returns:
 
 - Adds a soar_ros::Publisher() to the SoarRunner. - Template Parameters:
- T – 
- Parameters:
- output – 
- commandName – Matching of the Soar output-link command name, e.g. io.output-link.move matches to commandName “move”. 
 
- Returns:
 
 - Add a new soar_ros::Service. The callback on the output link is the service’s topic name. - Template Parameters:
- T – ROS2 service message type definition 
- Parameters:
- service – 
- Returns:
 
 - Add a new ROS2 Service with a custom callback command. - Template Parameters:
- T – 
- Parameters:
- service – 
- commandName – 
 
- Returns:
 
 - Add a new soar_ros::Client. The callback on the output link is the service’s topic name. - Template Parameters:
- T – ROS2 Service Message type definition 
- Parameters:
- service – 
- Returns:
 
 - Add a new soar_ros::Client with a custom callback command. - Template Parameters:
- T – 
- Parameters:
- service – 
- commandName – 
 
- Returns:
 
 - Add a new soar_ros::ActionClient with default command name. - Template Parameters:
- T – The action type 
- Parameters:
- action_client – The action client to add 
- Returns:
- true if successful 
 
 - Add a new soar_ros::ActionClient with a custom callback command. - Template Parameters:
- T – The action type 
- Parameters:
- action_client – The action client to add 
- commandName – The command name for Soar output-link 
 
- Returns:
- true if successful 
 
 - 
inline void startThread()
- Creates a new thread based on the SoarRunner::run() function that executes the Soar kernel. - Soar has a synchronous threading model, cf. https://soar.eecs.umich.edu/development/soar/ThreadsInSML/ 
 - 
inline void stopThread()
- Stops and joins SoarRunner::run() thread of Soar kernel via the SoarRunner::isRunning flag. 
 - 
inline void updateWorld()
- Soar update World function executed every step in the Soar execution cycle in SoarRunner::run() - Processes all outputs via SoarRunner::processOutputLinkChanges() and attaches new elements to the Soar input-link via SoarRunner::processInput(). 
 
- 
SoarRunner(const std::string &agent_name, const std::string &path_productions)