28#include <smacc2_msgs/msg/smacc_status.hpp> 
   29#include <smacc2_msgs/msg/smacc_transition_log_entry.hpp> 
   33using namespace std::chrono_literals;
 
   37: nh_(nullptr), stateSeqCounter_(0)
 
   39  rclcpp::NodeOptions node_options;
 
   46  nh_ = rclcpp::Node::make_shared(stateMachineName, node_options);  
 
   48    nh_->get_logger(), 
"Creating State Machine Base: " << 
nh_->get_fully_qualified_name());
 
   54  if (
nh_->get_parameter(
"run_mode", runMode))
 
   56    if (runMode == 
"debug")
 
   60    else if (runMode == 
"release")
 
   66      RCLCPP_ERROR(
nh_->get_logger(), 
"Incorrect run_mode value: %s", runMode.c_str());
 
   77  RCLCPP_INFO(
nh_->get_logger(), 
"Finishing State Machine");
 
   83    nh_->get_logger(), 
"[SmaccSignals] object signal disconnecting %ld", (
long)object_ptr);
 
   87    callbackSemaphore->finalize();
 
   92    RCLCPP_INFO(
nh_->get_logger(), 
"[SmaccSignals] no signals found %ld", (
long)object_ptr);
 
  104const std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> &
 
  112  std::lock_guard<std::recursive_mutex> lock(
m_mutex_);
 
  117      nh_->get_logger(), 
"[StateMachine] setting state active " 
  123      std::list<const SmaccStateInfo *> ancestorList;
 
  126      for (
auto & ancestor : ancestorList)
 
  128        status_msg_.current_states.push_back(ancestor->toShortName());
 
  136        status_msg_.global_variable_names.push_back(entry.first);
 
  138          entry.second.first());  
 
  149  smacc2_msgs::msg::SmaccTransitionLogEntry transitionLogEntry;
 
  150  transitionLogEntry.timestamp = this->
nh_->now();
 
  161  auto ros_clock = rclcpp::Clock::make_shared();
 
  168  RCLCPP_WARN_STREAM(
nh_->get_logger(), 
"State machine base creation:" << shortname);
 
  171    shortname + 
"/smacc/state_machine_description", 1);
 
  173    nh_->create_publisher<smacc2_msgs::msg::SmaccStatus>(shortname + 
"/smacc/status", 1);
 
  175    shortname + 
"/smacc/transition_log", 1);
 
  179    shortname + 
"/smacc/transition_log_history",
 
  182      std::placeholders::_2, std::placeholders::_3));
 
  186  const std::shared_ptr<rmw_request_id_t> ,
 
  187  const std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Request> ,
 
  188  std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Response> res)
 
  191    nh_->get_logger(), 
"Requesting Transition Log History, current size: %ld",
 
  192    this->transitionLogHistory_.size());
 
  198  std::lock_guard<std::recursive_mutex> lock(
m_mutex_);
 
  200  smacc2_msgs::msg::SmaccStateMachine state_machine_msg;
 
  204    state_machine_msg.states.begin(), state_machine_msg.states.end(),
 
  205    [](
auto & a, 
auto & b) { return a.index < b.index; });
 
  214  RCLCPP_DEBUG(
nh_->get_logger(), 
"-- locking SM: %s", msg.c_str());
 
  220  RCLCPP_DEBUG(
nh_->get_logger(), 
"-- unlocking SM: %s", msg.c_str());
 
std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > orthogonals_
 
smacc2::SMRunMode runMode_
 
virtual ~ISmaccStateMachine()
 
std::string getStateMachineName()
 
void publishTransition(const SmaccTransitionInfo &transitionInfo)
 
rclcpp::Publisher< smacc2_msgs::msg::SmaccStateMachine >::SharedPtr stateMachinePub_
 
std::shared_ptr< SmaccStateInfo > currentStateInfo_
 
rclcpp::Node::SharedPtr getNode()
 
std::map< std::string, std::pair< std::function< std::string()>, boost::any > > globalData_
 
rclcpp::Service< smacc2_msgs::srv::SmaccGetTransitionHistory >::SharedPtr transitionHistoryService_
 
virtual void onInitialize()
this function should be implemented by the user to create the orthogonals
 
std::vector< smacc2_msgs::msg::SmaccTransitionLogEntry > transitionLogHistory_
 
const std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > & getOrthogonals() const
 
std::recursive_mutex m_mutex_
 
rclcpp::Publisher< smacc2_msgs::msg::SmaccStatus >::SharedPtr stateMachineStatusPub_
 
ISmaccStateMachine(std::string stateMachineName, SignalDetector *signalDetector)
 
void lockStateMachine(std::string msg)
 
void disconnectSmaccSignalObject(void *object)
 
rclcpp::Node::SharedPtr nh_
 
void unlockStateMachine(std::string msg)
 
rclcpp::TimerBase::SharedPtr timer_
 
rclcpp::Publisher< smacc2_msgs::msg::SmaccTransitionLogEntry >::SharedPtr transitionLogPub_
 
void checkStateMachineConsistence()
 
SignalDetector * signalDetector_
 
std::map< void *, std::shared_ptr< CallbackCounterSemaphore > > stateCallbackConnections
 
void initializeROS(std::string smshortname)
 
smacc2_msgs::msg::SmaccStatus status_msg_
 
void state_machine_visualization()
 
std::shared_ptr< SmaccStateMachineInfo > stateMachineInfo_
 
void updateStatusMessage()
 
void getTransitionLogHistory(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< smacc2_msgs::srv::SmaccGetTransitionHistory::Request > req, std::shared_ptr< smacc2_msgs::srv::SmaccGetTransitionHistory::Response > res)
 
void initialize(ISmaccStateMachine *stateMachine)
 
std::string demangleSymbol()
 
void transitionInfoToMsg(const SmaccTransitionInfo &transition, smacc2_msgs::msg::SmaccTransition &transitionMsg)