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); //
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{
82 nh_->get_logger(), "[SmaccSignals] object signal disconnecting %ld", (long)object_ptr);
84 {
86 callbackSemaphore->finalize();
88 }
89 else
90 {
91 RCLCPP_INFO(nh_->get_logger(), "[SmaccSignals] no signals found %ld", (long)object_ptr);
92 }
93}
94
95rclcpp::Node::SharedPtr ISmaccStateMachine::getNode() { return this->nh_; }
96
98
100
102
103const std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> &
105{
106 return this->orthogonals_;
107}
108
110{
111 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
112
113 if (currentStateInfo_ != nullptr)
114 {
116 nh_->get_logger(), "[StateMachine] setting state active "
117 << ": " << currentStateInfo_->getFullPath());
118
120 {
121 status_msg_.current_states.clear();
122 std::list<const SmaccStateInfo *> ancestorList;
123 currentStateInfo_->getAncestors(ancestorList);
124
125 for (auto & ancestor : ancestorList)
126 {
127 status_msg_.current_states.push_back(ancestor->toShortName());
128 }
129
130 status_msg_.global_variable_names.clear();
131 status_msg_.global_variable_values.clear();
132
133 for (auto entry : this->globalData_)
134 {
135 status_msg_.global_variable_names.push_back(entry.first);
136 status_msg_.global_variable_values.push_back(
137 entry.second.first()); // <- invoke to_string()
138 }
139
140 status_msg_.header.stamp = this->nh_->now();
142 }
143 }
144}
145
147{
148 smacc2_msgs::msg::SmaccTransitionLogEntry transitionLogEntry;
149 transitionLogEntry.timestamp = this->nh_->now();
150 transitionInfoToMsg(transitionInfo, transitionLogEntry.transition);
151 this->transitionLogHistory_.push_back(transitionLogEntry);
152
154}
155
157
159{
160 auto ros_clock = rclcpp::Clock::make_shared();
161 timer_ =
162 rclcpp::create_timer(nh_, ros_clock, 0.5s, [=]() { this->state_machine_visualization(); });
163}
164
166{
167 RCLCPP_WARN_STREAM(nh_->get_logger(), "State machine base creation:" << shortname);
168 // STATE MACHINE TOPICS
169 stateMachinePub_ = nh_->create_publisher<smacc2_msgs::msg::SmaccStateMachine>(
170 shortname + "/smacc/state_machine_description", rclcpp::QoS(1));
171 stateMachineStatusPub_ = nh_->create_publisher<smacc2_msgs::msg::SmaccStatus>(
172 shortname + "/smacc/status", rclcpp::QoS(1));
173 transitionLogPub_ = nh_->create_publisher<smacc2_msgs::msg::SmaccTransitionLogEntry>(
174 shortname + "/smacc/transition_log", rclcpp::QoS(1));
175
176 // STATE MACHINE SERVICES
177 transitionHistoryService_ = nh_->create_service<smacc2_msgs::srv::SmaccGetTransitionHistory>(
178 shortname + "/smacc/transition_log_history",
179 std::bind(
180 &ISmaccStateMachine::getTransitionLogHistory, this, std::placeholders::_1,
181 std::placeholders::_2, std::placeholders::_3));
182}
183
185 const std::shared_ptr<rmw_request_id_t> /*request_header*/,
186 const std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Request> /*req*/,
187 std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Response> res)
188{
190 nh_->get_logger(), "Requesting Transition Log History, current size: %ld",
191 this->transitionLogHistory_.size());
192 res->history = this->transitionLogHistory_;
193}
194
196{
197 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
198
199 smacc2_msgs::msg::SmaccStateMachine state_machine_msg;
200 state_machine_msg.states = stateMachineInfo_->stateMsgs;
201
202 std::sort(
203 state_machine_msg.states.begin(), state_machine_msg.states.end(),
204 [](auto & a, auto & b) { return a.index < b.index; });
206
207 status_msg_.header.stamp = this->nh_->now();
209}
210
212{
213 RCLCPP_DEBUG(nh_->get_logger(), "-- locking SM: %s", msg.c_str());
214 m_mutex_.lock();
215}
216
218{
219 RCLCPP_DEBUG(nh_->get_logger(), "-- unlocking SM: %s", msg.c_str());
220 m_mutex_.unlock();
221}
222
224{
225 return demangleSymbol(typeid(*this).name());
226}
227
229{
230 // transition from an orthogonal that doesn’t exist.
231 // transition from a source that doesn’t exist.
232
233 // std::stringstream errorbuffer;
234 // bool errorFound = false;
235
236 // for (auto &stentry : this->stateMachineInfo_->states)
237 // {
238 // auto stinfo = stentry.second;
239
240 // for (auto &transition : stinfo->transitions_)
241 // {
242 // auto evinfo = transition.eventInfo;
243 // bool found = false;
244 // for (auto &orthogonal : orthogonals_)
245 // {
246 // if (orthogonal.first == evinfo->getOrthogonalName())
247 // {
248 // found = true;
249 // break;
250 // }
251 // }
252
253 // if (!found)
254 // {
255 // errorbuffer << "---------" << std::endl
256 // << "[Consistency Checking] Transition event refers not existing orthogonal." << std::endl
257 // << "State: " << demangleType(*stinfo->tid_) << std::endl
258 // << "Transition: " << transition.transitionTypeInfo->getFullName() << std::endl
259 // << "Orthogonal: " << evinfo->getOrthogonalName() << std::endl
260 // << "---------" << std::endl;
261
262 // errorFound = true;
263 // }
264 // //std::string getEventSourceName();
265 // //std::string getOrthogonalName();
266 // }
267 // }
268
269 // if (errorFound)
270 // {
271 // RCLCPP_WARN_STREAM(nh_->get_logger(),"== STATE MACHINE CONSISTENCY CHECK: ==" << std::endl
272 // << errorbuffer.str() << std::endl
273 // << "=================");
274 // }
275 // cb from a client that doesn’t exist – don’t worry about making clients dynamically.
276}
277
278} // 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_
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)