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)

ROS2 interface to get current Soar kernel status (run/ stop) via.

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!

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)

ROS2 Service interface to stop Soar kernel if it is currently running via.

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".

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)

ROS2 Service interface to start (run) Soar kernel if it is currenlty stopped.

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".

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)

Enable external control to start the debugger and stop the run thread via.

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