28#include <smacc2_msgs/msg/smacc_status.hpp>
29#include <smacc2_msgs/msg/smacc_transition_log_entry.hpp>
33using namespace std::chrono_literals;
36 std::string stateMachineName,
SignalDetector * signalDetector, rclcpp::NodeOptions nodeOptions)
37: nh_(nullptr), stateSeqCounter_(0)
45 nh_ = rclcpp::Node::make_shared(stateMachineName, nodeOptions);
47 nh_->get_logger(),
"Creating State Machine Base: " <<
nh_->get_fully_qualified_name());
53 if (
nh_->get_parameter(
"run_mode", runMode))
55 if (runMode ==
"debug")
59 else if (runMode ==
"release")
65 RCLCPP_ERROR(
nh_->get_logger(),
"Incorrect run_mode value: %s", runMode.c_str());
76 RCLCPP_INFO(
nh_->get_logger(),
"Finishing State Machine");
82 nh_->get_logger(),
"[SmaccSignals] object signal disconnecting %ld", (
long)object_ptr);
86 callbackSemaphore->finalize();
91 RCLCPP_INFO(
nh_->get_logger(),
"[SmaccSignals] no signals found %ld", (
long)object_ptr);
103const std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> &
111 std::lock_guard<std::recursive_mutex> lock(
m_mutex_);
116 nh_->get_logger(),
"[StateMachine] setting state active "
122 std::list<const SmaccStateInfo *> ancestorList;
125 for (
auto & ancestor : ancestorList)
127 status_msg_.current_states.push_back(ancestor->toShortName());
135 status_msg_.global_variable_names.push_back(entry.first);
137 entry.second.first());
148 smacc2_msgs::msg::SmaccTransitionLogEntry transitionLogEntry;
149 transitionLogEntry.timestamp = this->
nh_->now();
160 auto ros_clock = rclcpp::Clock::make_shared();
167 RCLCPP_WARN_STREAM(
nh_->get_logger(),
"State machine base creation:" << shortname);
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());
197 std::lock_guard<std::recursive_mutex> lock(
m_mutex_);
199 smacc2_msgs::msg::SmaccStateMachine state_machine_msg;
203 state_machine_msg.states.begin(), state_machine_msg.states.end(),
204 [](
auto & a,
auto & b) { return a.index < b.index; });
213 RCLCPP_DEBUG(
nh_->get_logger(),
"-- locking SM: %s", msg.c_str());
219 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, 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)