22#include <boost/any.hpp> 
   32#include <smacc2_msgs/msg/smacc_state_machine.hpp> 
   33#include <smacc2_msgs/msg/smacc_status.hpp> 
   34#include <smacc2_msgs/msg/smacc_transition_log_entry.hpp> 
   35#include <smacc2_msgs/srv/smacc_get_transition_history.hpp> 
   77  template <
typename TOrthogonal>
 
   80  const std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> & 
getOrthogonals() 
const;
 
   82  template <
typename SmaccComponentType>
 
   83  void requiresComponent(SmaccComponentType *& storage, 
bool throwsException = 
false);
 
   85  template <
typename EventType>
 
   88  template <
typename EventType>
 
   99  template <
typename StateField, 
typename BehaviorType>
 
  114    const std::shared_ptr<rmw_request_id_t> request_header,
 
  115    const std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Request> req,
 
  116    std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Response> res);
 
  118  template <
typename TSmaccSignal, 
typename TMemberFunctionPrototype, 
typename TSmaccObjectType>
 
  120    TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * 
object);
 
  124  template <
typename StateType>
 
  127  template <
typename StateType>
 
  130  template <
typename StateType>
 
  133  template <
typename StateType>
 
  136  template <
typename StateType>
 
  139  template <
typename StateType>
 
  148  template <
typename InitialStateType>
 
  151  rclcpp::Node::SharedPtr 
getNode();
 
  164  template <
typename TOrthogonal>
 
  168  rclcpp::Node::SharedPtr 
nh_;
 
  185  std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> 
orthogonals_;
 
  199  std::map<std::string, std::pair<std::function<std::string()>, boost::any>> 
globalData_;
 
  215  template <
typename EventType>
 
std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > orthogonals_
 
smacc2::SMRunMode runMode_
 
std::vector< ISmaccState * > currentState_
 
std::recursive_mutex eventQueueMutex_
 
virtual ~ISmaccStateMachine()
 
std::string getStateMachineName()
 
uint64_t stateSeqCounter_
 
bool getGlobalSMData(std::string name, T &ret)
 
void publishTransition(const SmaccTransitionInfo &transitionInfo)
 
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
 
StateMachineInternalAction stateMachineCurrentAction
 
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_
 
void notifyOnStateExitting(StateType *state)
 
rclcpp::Service< smacc2_msgs::srv::SmaccGetTransitionHistory >::SharedPtr transitionHistoryService_
 
void setGlobalSMData(std::string name, T value)
 
virtual void onInitialize()
this function should be implemented by the user to create the orthogonals
 
TOrthogonal * getOrthogonal()
 
std::vector< smacc2_msgs::msg::SmaccTransitionLogEntry > transitionLogHistory_
 
void buildStateMachineInfo()
 
void notifyOnRuntimeConfigurationFinished(StateType *state)
 
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_
 
void notifyOnStateExited(StateType *state)
 
void lockStateMachine(std::string msg)
 
void notifyOnStateEntryEnd(StateType *state)
 
void propagateEventToStateReactors(ISmaccState *st, EventType *ev)
 
void disconnectSmaccSignalObject(void *object)
 
const SmaccStateMachineInfo & getStateMachineInfo()
 
rclcpp::Node::SharedPtr nh_
 
uint64_t getCurrentStateCounter() const
 
std::shared_ptr< SmaccStateInfo > getCurrentStateInfo()
 
void unlockStateMachine(std::string msg)
 
rclcpp::TimerBase::SharedPtr timer_
 
rclcpp::Publisher< smacc2_msgs::msg::SmaccTransitionLogEntry >::SharedPtr transitionLogPub_
 
ISmaccState * getCurrentState() const
 
void checkStateMachineConsistence()
 
SignalDetector * signalDetector_
 
std::map< void *, std::shared_ptr< CallbackCounterSemaphore > > stateCallbackConnections
 
rclcpp::Logger getLogger()
 
void notifyOnRuntimeConfigured(StateType *state)
 
void initializeROS(std::string smshortname)
 
smacc2_msgs::msg::SmaccStatus status_msg_
 
void state_machine_visualization()
 
std::shared_ptr< SmaccStateMachineInfo > stateMachineInfo_
 
void postEvent(EventType *ev, EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)
 
void updateStatusMessage()
 
std::recursive_mutex & getMutex()
 
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 requiresComponent(SmaccComponentType *&storage, bool throwsException=false)
 
void notifyOnStateEntryStart(StateType *state)
 
StateMachineInternalAction