ROS Interface

Soar Kernel Status

void soar_ros::SoarRunner::getSoarKernelStatus([[maybe_unused]] const std::shared_ptr<rmw_request_id_t> request_header, [[maybe_unused]] 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.

Run Soar Kernel

void soar_ros::SoarRunner::runSoarKernel([[maybe_unused]] const std::shared_ptr<rmw_request_id_t> request_header, [[maybe_unused]] 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.

Stop Soar Kernel

void soar_ros::SoarRunner::stopSoarKernel([[maybe_unused]] const std::shared_ptr<rmw_request_id_t> request_header, [[maybe_unused]] 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.

Launch Soar Debugger

void soar_ros::SoarRunner::debuggerLaunch([[maybe_unused]] const std::shared_ptr<rmw_request_id_t> request_header, [[maybe_unused]] 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.