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)
47 nh_->get_logger(),
"Creating State Machine Base: " <<
nh_->get_fully_qualified_name());
82 nh_->get_logger(),
"[SmaccSignals] object signal disconnecting %ld", (
long)
object_ptr);
103const std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> &
116 nh_->get_logger(),
"[StateMachine] setting state active "
137 entry.second.first());
160 auto ros_clock = rclcpp::Clock::make_shared();
170 shortname +
"/smacc/state_machine_description", rclcpp::QoS(1));
172 shortname +
"/smacc/status", rclcpp::QoS(1));
174 shortname +
"/smacc/transition_log", rclcpp::QoS(1));
178 shortname +
"/smacc/transition_log_history",
181 std::placeholders::_2, std::placeholders::_3));
185 const std::shared_ptr<rmw_request_id_t> ,
186 const std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Request> ,
187 std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Response>
res)
190 nh_->get_logger(),
"Requesting Transition Log History, current size: %ld",
191 this->transitionLogHistory_.size());
204 [](
auto &
a,
auto &
b) { return a.index < b.index; });
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, rclcpp::NodeOptions nodeOptions=rclcpp::NodeOptions())
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)