SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | Friends | List of all members
smacc2::ISmaccOrthogonal Class Reference

#include <smacc_orthogonal.hpp>

Inheritance diagram for smacc2::ISmaccOrthogonal:
Inheritance graph
Collaboration diagram for smacc2::ISmaccOrthogonal:
Collaboration graph

Public Member Functions

void setStateMachine (ISmaccStateMachine *value)
 
ISmaccStateMachinegetStateMachine ()
 
void initState (ISmaccState *state)
 
void addClientBehavior (std::shared_ptr< smacc2::ISmaccClientBehavior > clientBehavior)
 
void runtimeConfigure ()
 
void onEntry ()
 
void onExit ()
 
void onDispose ()
 
virtual std::string getName () const
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage)
 
template<typename SmaccClientType >
bool requiresClient (SmaccClientType *&storage)
 
const std::vector< std::shared_ptr< smacc2::ISmaccClient > > & getClients ()
 
const std::vector< std::vector< std::shared_ptr< smacc2::ISmaccClientBehavior > > > & getClientBehaviors () const
 
template<typename T >
void setGlobalSMData (std::string name, T value)
 
template<typename T >
bool getGlobalSMData (std::string name, T &ret)
 
template<typename TClientBehavior >
TClientBehaviorgetClientBehavior (int index=0)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger ()
 

Protected Member Functions

virtual void onInitialize ()
 
void initializeClients ()
 
template<typename TOrthogonal , typename TClient >
void assignClientToOrthogonal (TClient *client)
 

Protected Attributes

std::vector< std::shared_ptr< smacc2::ISmaccClient > > clients_
 

Private Attributes

ISmaccStateMachinestateMachine_
 
std::vector< std::vector< std::shared_ptr< smacc2::ISmaccClientBehavior > > > clientBehaviors_
 
std::mutex mutex_
 

Friends

class ISmaccStateMachine
 

Detailed Description

Definition at line 27 of file smacc_orthogonal.hpp.

Member Function Documentation

◆ addClientBehavior()

void smacc2::ISmaccOrthogonal::addClientBehavior ( std::shared_ptr< smacc2::ISmaccClientBehavior clientBehavior)

Definition at line 49 of file orthogonal.cpp.

50{
51 std::lock_guard<std::mutex> lock(this->mutex_);
52
53 if (clBehavior != nullptr)
54 {
55 RCLCPP_INFO(
56 getLogger(), "[Orthogonal %s] adding client behavior: %s", this->getName().c_str(),
57 clBehavior->getName().c_str());
58 clBehavior->stateMachine_ = this->getStateMachine();
59 clBehavior->currentOrthogonal = this;
60 clBehavior->currentState = clBehavior->stateMachine_->getCurrentState();
61
62 clientBehaviors_.back().push_back(clBehavior);
63 }
64 else
65 {
66 RCLCPP_INFO(
67 getLogger(), "[orthogonal %s] no client behaviors in this state", this->getName().c_str());
68 }
69}
ISmaccStateMachine * getStateMachine()
std::vector< std::vector< std::shared_ptr< smacc2::ISmaccClientBehavior > > > clientBehaviors_
virtual std::string getName() const

References clientBehaviors_, getLogger(), getName(), getStateMachine(), and mutex_.

Here is the call graph for this function:

◆ assignClientToOrthogonal()

void smacc2::ISmaccOrthogonal::assignClientToOrthogonal ( TClient client)
protected

Definition at line 82 of file smacc_orthogonal_impl.hpp.

83{
84 client->setStateMachine(getStateMachine());
85 client->setOrthogonal(this);
86
87 client->template onOrthogonalAllocation<TOrthogonal, TClient>();
88}

References getStateMachine().

Here is the call graph for this function:

◆ getClientBehavior()

TClientBehavior * smacc2::ISmaccOrthogonal::getClientBehavior ( int  index = 0)

Definition at line 91 of file smacc_orthogonal_impl.hpp.

92{
93 int i = 0;
94 for (auto & cb : this->clientBehaviors_.back())
95 {
96 auto * ret = dynamic_cast<TClientBehavior *>(cb.get());
97 if (ret != nullptr)
98 {
99 if (i == index)
100 return ret;
101 else
102 i++;
103 }
104 }
105
106 return nullptr;
107}

References clientBehaviors_.

◆ getClientBehaviors()

const std::vector< std::vector< std::shared_ptr< smacc2::ISmaccClientBehavior > > > & smacc2::ISmaccOrthogonal::getClientBehaviors ( ) const
inline

Definition at line 114 of file smacc_orthogonal_impl.hpp.

115{
116 return this->clientBehaviors_;
117}

References clientBehaviors_.

◆ getClients()

const std::vector< std::shared_ptr< smacc2::ISmaccClient > > & smacc2::ISmaccOrthogonal::getClients ( )
inline

Definition at line 108 of file smacc_orthogonal_impl.hpp.

109{
110 return clients_;
111}
std::vector< std::shared_ptr< smacc2::ISmaccClient > > clients_

References clients_.

◆ getGlobalSMData()

template<typename T >
bool smacc2::ISmaccOrthogonal::getGlobalSMData ( std::string  name,
T ret 
)

Definition at line 126 of file smacc_orthogonal_impl.hpp.

127{
128 return this->getStateMachine()->getGlobalSMData(name, ret);
129}
bool getGlobalSMData(std::string name, T &ret)

References smacc2::ISmaccStateMachine::getGlobalSMData(), and getStateMachine().

Here is the call graph for this function:

◆ getLogger()

rclcpp::Logger smacc2::ISmaccOrthogonal::getLogger ( )
inline

Definition at line 71 of file smacc_orthogonal.hpp.

71{ return getNode()->get_logger(); }
rclcpp::Node::SharedPtr getNode()

References getNode().

Referenced by addClientBehavior(), smacc2::Orthogonal< TOrthogonal >::createClient(), initState(), onEntry(), onExit(), requiresClient(), requiresComponent(), and runtimeConfigure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getName()

std::string smacc2::ISmaccOrthogonal::getName ( ) const
virtual

Definition at line 81 of file orthogonal.cpp.

81{ return demangleSymbol(typeid(*this).name()); }
std::string demangleSymbol()

References smacc2::introspection::demangleSymbol().

Referenced by addClientBehavior(), initState(), and runtimeConfigure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getNode()

rclcpp::Node::SharedPtr smacc2::ISmaccOrthogonal::getNode ( )

Definition at line 47 of file orthogonal.cpp.

47{ return this->stateMachine_->getNode(); }
ISmaccStateMachine * stateMachine_
rclcpp::Node::SharedPtr getNode()

References smacc2::ISmaccStateMachine::getNode(), and stateMachine_.

Referenced by getLogger().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getStateMachine()

ISmaccStateMachine * smacc2::ISmaccOrthogonal::getStateMachine ( )
inline

Definition at line 132 of file smacc_orthogonal_impl.hpp.

132{ return this->stateMachine_; }

References stateMachine_.

Referenced by addClientBehavior(), assignClientToOrthogonal(), getGlobalSMData(), onDispose(), requiresClient(), and setGlobalSMData().

Here is the caller graph for this function:

◆ initializeClients()

void smacc2::ISmaccOrthogonal::initializeClients ( )
protected

Definition at line 39 of file orthogonal.cpp.

40{
41 for (auto & c : this->clients_)
42 {
43 c->initialize();
44 }
45}

References clients_.

Referenced by setStateMachine().

Here is the caller graph for this function:

◆ initState()

void smacc2::ISmaccOrthogonal::initState ( ISmaccState state)

Definition at line 73 of file orthogonal.cpp.

74{
75 RCLCPP_INFO(
76 getLogger(), "[Orthogonal %s] initState: %s", this->getName().c_str(),
77 state->getClassName().c_str());
78 clientBehaviors_.push_back(std::vector<std::shared_ptr<smacc2::ISmaccClientBehavior>>());
79}

References clientBehaviors_, getLogger(), and getName().

Here is the call graph for this function:

◆ onDispose()

void smacc2::ISmaccOrthogonal::onDispose ( )

Definition at line 165 of file orthogonal.cpp.

166{
167 for (auto & clBehavior : clientBehaviors_.back())
168 {
169 clBehavior->dispose();
170 this->getStateMachine()->disconnectSmaccSignalObject((void *)clBehavior.get());
171 }
172
173 clientBehaviors_.back().clear();
174 clientBehaviors_.pop_back();
175}
void disconnectSmaccSignalObject(void *object)

References clientBehaviors_, smacc2::ISmaccStateMachine::disconnectSmaccSignalObject(), and getStateMachine().

Here is the call graph for this function:

◆ onEntry()

void smacc2::ISmaccOrthogonal::onEntry ( )

Definition at line 97 of file orthogonal.cpp.

98{
99 std::lock_guard<std::mutex> lock(this->mutex_);
100
101 if (clientBehaviors_.back().size() > 0)
102 {
103 for (auto & clBehavior : clientBehaviors_.back())
104 {
105 RCLCPP_INFO(
106 getLogger(), "[Orthogonal %s] OnEntry, current Behavior: %s", orthogonalName, cbName);
107
108 try
109 {
111 clBehavior->executeOnEntry();
112 }
113 catch (const std::exception & e)
114 {
115 RCLCPP_ERROR(
116 getLogger(),
117 "[ClientBehavior %s] Exception on Entry - continuing with next client behavior. "
118 "Exception info: "
119 "%s",
120 cbName, e.what());
121 }
123 }
124 }
125 else
126 {
127 RCLCPP_INFO(
128 getLogger(), "[Orthogonal %s] OnEntry -> empty orthogonal (no client behavior) ",
130 }
131}
#define orthogonalName
#define statename
#define cbName
void TRACEPOINT(spinOnce)
smacc2_client_behavior_on_entry_start
smacc2_client_behavior_on_entry_end

References cbName, clientBehaviors_, getLogger(), mutex_, orthogonalName, smacc2_client_behavior_on_entry_end, smacc2_client_behavior_on_entry_start, statename, and TRACEPOINT().

Here is the call graph for this function:

◆ onExit()

void smacc2::ISmaccOrthogonal::onExit ( )

Definition at line 133 of file orthogonal.cpp.

134{
135 std::lock_guard<std::mutex> lock(this->mutex_);
136
137 if (clientBehaviors_.back().size() > 0)
138 {
139 for (auto & clBehavior : clientBehaviors_.back())
140 {
141 RCLCPP_INFO(
142 getLogger(), "[Orthogonal %s] OnExit, current Behavior: %s", orthogonalName, cbName);
143 try
144 {
146 clBehavior->executeOnExit();
147 }
148 catch (const std::exception & e)
149 {
150 RCLCPP_ERROR(
151 getLogger(),
152 "[ClientBehavior %s] Exception onExit - continuing with next client behavior. Exception "
153 "info: %s",
154 cbName, e.what());
155 }
157 }
158 }
159 else
160 {
161 RCLCPP_INFO(getLogger(), "[Orthogonal %s] OnExit", orthogonalName);
162 }
163}
smacc2_client_behavior_on_exit_end
smacc2_client_behavior_on_exit_start

References cbName, clientBehaviors_, getLogger(), mutex_, orthogonalName, smacc2_client_behavior_on_exit_end, smacc2_client_behavior_on_exit_start, statename, and TRACEPOINT().

Here is the call graph for this function:

◆ onInitialize()

void smacc2::ISmaccOrthogonal::onInitialize ( )
protectedvirtual

Definition at line 71 of file orthogonal.cpp.

71{}

Referenced by setStateMachine().

Here is the caller graph for this function:

◆ requiresClient()

bool smacc2::ISmaccOrthogonal::requiresClient ( SmaccClientType *&  storage)

Definition at line 29 of file smacc_orthogonal_impl.hpp.

30{
31 for (auto & client : clients_)
32 {
33 storage = dynamic_cast<SmaccClientType *>(client.get());
34 if (storage != nullptr) return true;
35 }
36
37 auto requiredClientName = demangledTypeName<SmaccClientType>();
38 RCLCPP_WARN_STREAM(
39 getLogger(), "Required client ["
40 << requiredClientName
41 << "] not found in current orthogonal. Searching in other orthogonals.");
42
43 for (auto & orthoentry : this->getStateMachine()->getOrthogonals())
44 {
45 for (auto & client : orthoentry.second->getClients())
46 {
47 storage = dynamic_cast<SmaccClientType *>(client.get());
48 if (storage != nullptr)
49 {
50 RCLCPP_WARN_STREAM(
51 getLogger(),
52 "Required client [" << requiredClientName << "] found in other orthogonal.");
53 return true;
54 }
55 }
56 }
57
58 RCLCPP_ERROR_STREAM(
59 getLogger(), "Required client ["
60 << requiredClientName
61 << "] not found even in other orthogonals. Returning null pointer. If the "
62 "requested client is used may result in a segmentation fault.");
63 return false;
64}
const std::vector< std::shared_ptr< smacc2::ISmaccClient > > & getClients()

References clients_, getLogger(), smacc2::ISmaccStateMachine::getOrthogonals(), and getStateMachine().

Referenced by smacc2::ISmaccClient::requiresClient(), and smacc2::ISmaccClientBehavior::requiresClient().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ requiresComponent()

void smacc2::ISmaccOrthogonal::requiresComponent ( SmaccComponentType *&  storage)

Definition at line 67 of file smacc_orthogonal_impl.hpp.

68{
69 if (stateMachine_ == nullptr)
70 {
71 RCLCPP_ERROR(
72 getLogger(),
73 "Cannot use the requiresComponent funcionality from an orthogonal before onInitialize");
74 }
75 else
76 {
78 }
79}
void requiresComponent(SmaccComponentType *&storage, bool throwsExceptionIfNotExist=false)

References getLogger(), smacc2::ISmaccStateMachine::requiresComponent(), and stateMachine_.

Here is the call graph for this function:

◆ runtimeConfigure()

void smacc2::ISmaccOrthogonal::runtimeConfigure ( )

Definition at line 83 of file orthogonal.cpp.

84{
85 std::lock_guard<std::mutex> lock(this->mutex_);
86
87 for (auto & clBehavior : clientBehaviors_.back())
88 {
89 RCLCPP_INFO(
90 getLogger(), "[Orthogonal %s] runtimeConfigure, current Behavior: %s",
91 this->getName().c_str(), clBehavior->getName().c_str());
92
93 clBehavior->runtimeConfigure();
94 }
95}

References clientBehaviors_, getLogger(), getName(), and mutex_.

Here is the call graph for this function:

◆ setGlobalSMData()

template<typename T >
void smacc2::ISmaccOrthogonal::setGlobalSMData ( std::string  name,
T  value 
)

Definition at line 120 of file smacc_orthogonal_impl.hpp.

121{
122 this->getStateMachine()->setGlobalSMData(name, value);
123}
void setGlobalSMData(std::string name, T value)

References getStateMachine(), and smacc2::ISmaccStateMachine::setGlobalSMData().

Here is the call graph for this function:

◆ setStateMachine()

void smacc2::ISmaccOrthogonal::setStateMachine ( ISmaccStateMachine value)

Definition at line 32 of file orthogonal.cpp.

33{
34 this->stateMachine_ = value;
35 this->onInitialize();
36 this->initializeClients();
37}
virtual void onInitialize()

References initializeClients(), onInitialize(), and stateMachine_.

Here is the call graph for this function:

Friends And Related Symbol Documentation

◆ ISmaccStateMachine

friend class ISmaccStateMachine
friend

Definition at line 87 of file smacc_orthogonal.hpp.

Member Data Documentation

◆ clientBehaviors_

std::vector<std::vector<std::shared_ptr<smacc2::ISmaccClientBehavior> > > smacc2::ISmaccOrthogonal::clientBehaviors_
private

◆ clients_

std::vector<std::shared_ptr<smacc2::ISmaccClient> > smacc2::ISmaccOrthogonal::clients_
protected

◆ mutex_

std::mutex smacc2::ISmaccOrthogonal::mutex_
private

Definition at line 89 of file smacc_orthogonal.hpp.

Referenced by addClientBehavior(), onEntry(), onExit(), and runtimeConfigure().

◆ stateMachine_

ISmaccStateMachine* smacc2::ISmaccOrthogonal::stateMachine_
private

Definition at line 84 of file smacc_orthogonal.hpp.

Referenced by getNode(), getStateMachine(), requiresComponent(), and setStateMachine().


The documentation for this class was generated from the following files: