SMACC2
Loading...
Searching...
No Matches
smacc_state_machine.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#include <rcl/time.h>
22#include <chrono>
23#include <functional>
28#include <smacc2_msgs/msg/smacc_status.hpp>
29#include <smacc2_msgs/msg/smacc_transition_log_entry.hpp>
30
31namespace smacc2
32{
33using namespace std::chrono_literals;
34using namespace smacc2::introspection;
36 std::string stateMachineName, SignalDetector * signalDetector, rclcpp::NodeOptions nodeOptions)
37: nh_(nullptr), stateSeqCounter_(0)
38{
39 // This enables loading arbitrary parameters
40 // However, best practice would be to declare parameters in the corresponding classes
41 // and provide descriptions about expected use
42 // TODO(henningkayser): remove once all parameters are declared inside the components
43 // node_options.automatically_declare_parameters_from_overrides(true);
44
45 nh_ = rclcpp::Node::make_shared(stateMachineName, nodeOptions); //
46 RCLCPP_INFO_STREAM(
47 nh_->get_logger(), "Creating state machine base: " << nh_->get_fully_qualified_name());
48
49 signalDetector_ = signalDetector;
51
52 std::string runMode;
53 if (nh_->get_parameter("run_mode", runMode))
54 {
55 if (runMode == "debug")
56 {
58 }
59 else if (runMode == "release")
60 {
62 }
63 else
64 {
65 RCLCPP_ERROR(nh_->get_logger(), "Incorrect run_mode value: %s", runMode.c_str());
66 }
67 }
68 else
69 {
71 }
72}
73
75{
76 RCLCPP_INFO(nh_->get_logger(), "Finishing State Machine");
77}
78
80{
81 RCLCPP_INFO(nh_->get_logger(), "[SmaccSignal] Object signal disconnecting %ld", (long)object_ptr);
82 if (stateCallbackConnections.count(object_ptr) > 0)
83 {
84 auto callbackSemaphore = stateCallbackConnections[object_ptr];
85 callbackSemaphore->finalize();
86 stateCallbackConnections.erase(object_ptr);
87 }
88 else
89 {
90 RCLCPP_INFO(nh_->get_logger(), "[SmaccSignal] No signals found %ld", (long)object_ptr);
91 }
92}
93
94rclcpp::Node::SharedPtr ISmaccStateMachine::getNode() { return this->nh_; }
95
97
99
101
102const std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> &
104{
105 return this->orthogonals_;
106}
107
109{
110 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
111
112 if (currentStateInfo_ != nullptr)
113 {
114 RCLCPP_WARN_STREAM(
115 nh_->get_logger(),
116 "[StateMachine] Setting state active: " << currentStateInfo_->getFullPath());
117
119 {
120 status_msg_.current_states.clear();
121 std::list<const SmaccStateInfo *> ancestorList;
122 currentStateInfo_->getAncestors(ancestorList);
123
124 for (auto & ancestor : ancestorList)
125 {
126 status_msg_.current_states.push_back(ancestor->toShortName());
127 }
128
129 status_msg_.global_variable_names.clear();
130 status_msg_.global_variable_values.clear();
131
132 for (auto entry : this->globalData_)
133 {
134 status_msg_.global_variable_names.push_back(entry.first);
135 status_msg_.global_variable_values.push_back(
136 entry.second.first()); // <- invoke to_string()
137 }
138
139 status_msg_.header.stamp = this->nh_->now();
141 }
142 }
143}
144
146{
147 smacc2_msgs::msg::SmaccTransitionLogEntry transitionLogEntry;
148 transitionLogEntry.timestamp = this->nh_->now();
149 transitionInfoToMsg(transitionInfo, transitionLogEntry.transition);
150 this->transitionLogHistory_.push_back(transitionLogEntry);
151
152 transitionLogPub_->publish(transitionLogEntry);
153}
154
156
158{
159 auto ros_clock = rclcpp::Clock::make_shared();
160 timer_ =
161 rclcpp::create_timer(nh_, ros_clock, 0.5s, [=]() { this->state_machine_visualization(); });
162}
163
164void ISmaccStateMachine::initializeROS(std::string shortname)
165{
166 RCLCPP_WARN_STREAM(nh_->get_logger(), "State machine base creation: " << shortname);
167 // STATE MACHINE TOPICS
168 stateMachinePub_ = nh_->create_publisher<smacc2_msgs::msg::SmaccStateMachine>(
169 shortname + "/smacc/state_machine_description", rclcpp::QoS(1));
170 stateMachineStatusPub_ = nh_->create_publisher<smacc2_msgs::msg::SmaccStatus>(
171 shortname + "/smacc/status", rclcpp::QoS(1));
172 transitionLogPub_ = nh_->create_publisher<smacc2_msgs::msg::SmaccTransitionLogEntry>(
173 shortname + "/smacc/transition_log", rclcpp::QoS(1));
174
175 eventsLogPub_ = nh_->create_publisher<smacc2_msgs::msg::SmaccEvent>(
176 shortname + "/smacc/event_log", rclcpp::QoS(100));
177
178 // STATE MACHINE SERVICES
179 transitionHistoryService_ = nh_->create_service<smacc2_msgs::srv::SmaccGetTransitionHistory>(
180 shortname + "/smacc/transition_log_history",
181 std::bind(
182 &ISmaccStateMachine::getTransitionLogHistory, this, std::placeholders::_1,
183 std::placeholders::_2, std::placeholders::_3));
184}
185
187 const std::shared_ptr<rmw_request_id_t> /*request_header*/,
188 const std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Request> /*req*/,
189 std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Response> res)
190{
191 RCLCPP_WARN(
192 nh_->get_logger(), "Requesting transition log history, current size: %ld",
193 this->transitionLogHistory_.size());
194 res->history = this->transitionLogHistory_;
195}
196
198{
199 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
200
201 smacc2_msgs::msg::SmaccStateMachine state_machine_msg;
202 state_machine_msg.states = stateMachineInfo_->stateMsgs;
203
204 std::sort(
205 state_machine_msg.states.begin(), state_machine_msg.states.end(),
206 [](auto & a, auto & b) { return a.index < b.index; });
207 stateMachinePub_->publish(state_machine_msg);
208
209 status_msg_.header.stamp = this->nh_->now();
211}
212
214{
215 RCLCPP_DEBUG(nh_->get_logger(), "-- locking SM: %s", msg.c_str());
216 m_mutex_.lock();
217}
218
220{
221 RCLCPP_DEBUG(nh_->get_logger(), "-- unlocking SM: %s", msg.c_str());
222 m_mutex_.unlock();
223}
224
226{
227 return demangleSymbol(typeid(*this).name());
228}
229
231{
232 // transition from an orthogonal that doesn’t exist.
233 // transition from a source that doesn’t exist.
234
235 // std::stringstream errorbuffer;
236 // bool errorFound = false;
237
238 // for (auto &stentry : this->stateMachineInfo_->states)
239 // {
240 // auto stinfo = stentry.second;
241
242 // for (auto &transition : stinfo->transitions_)
243 // {
244 // auto evinfo = transition.eventInfo;
245 // bool found = false;
246 // for (auto &orthogonal : orthogonals_)
247 // {
248 // if (orthogonal.first == evinfo->getOrthogonalName())
249 // {
250 // found = true;
251 // break;
252 // }
253 // }
254
255 // if (!found)
256 // {
257 // errorbuffer << "---------" << std::endl
258 // << "[Consistency Checking] Transition event refers not existing orthogonal." << std::endl
259 // << "State: " << demangleType(*stinfo->tid_) << std::endl
260 // << "Transition: " << transition.transitionTypeInfo->getFullName() << std::endl
261 // << "Orthogonal: " << evinfo->getOrthogonalName() << std::endl
262 // << "---------" << std::endl;
263
264 // errorFound = true;
265 // }
266 // //std::string getEventSourceName();
267 // //std::string getOrthogonalName();
268 // }
269 // }
270
271 // if (errorFound)
272 // {
273 // RCLCPP_WARN_STREAM(nh_->get_logger(),"== STATE MACHINE CONSISTENCY CHECK: ==" << std::endl
274 // << errorbuffer.str() << std::endl
275 // << "=================");
276 // }
277 // cb from a client that doesn’t exist – don’t worry about making clients dynamically.
278}
279
280} // namespace smacc2
std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > orthogonals_
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
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)
void unlockStateMachine(std::string msg)
rclcpp::TimerBase::SharedPtr timer_
rclcpp::Publisher< smacc2_msgs::msg::SmaccTransitionLogEntry >::SharedPtr transitionLogPub_
std::map< void *, std::shared_ptr< CallbackCounterSemaphore > > stateCallbackConnections
void initializeROS(std::string smshortname)
smacc2_msgs::msg::SmaccStatus status_msg_
std::shared_ptr< SmaccStateMachineInfo > stateMachineInfo_
rclcpp::Publisher< smacc2_msgs::msg::SmaccEvent >::SharedPtr eventsLogPub_
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)