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

#include <smacc_orthogonal.h>

Inheritance diagram for smacc::ISmaccOrthogonal:
Inheritance graph
Collaboration diagram for smacc::ISmaccOrthogonal:
Collaboration graph

Public Member Functions

void setStateMachine (ISmaccStateMachine *value)
 
ISmaccStateMachinegetStateMachine ()
 
void initState (ISmaccState *state)
 
void addClientBehavior (std::shared_ptr< smacc::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< smacc::ISmaccClient > > & getClients ()
 
const std::vector< std::vector< std::shared_ptr< smacc::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 >
TClientBehavior * getClientBehavior ()
 

Protected Member Functions

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

Protected Attributes

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

Private Attributes

ISmaccStateMachinestateMachine_
 
std::vector< std::vector< std::shared_ptr< smacc::ISmaccClientBehavior > > > clientBehaviors_
 

Friends

class ISmaccStateMachine
 

Detailed Description

Definition at line 13 of file smacc_orthogonal.h.

Member Function Documentation

◆ addClientBehavior()

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

Definition at line 13 of file orthogonal.cpp.

14 {
15 if (clBehavior != nullptr)
16 {
17 ROS_INFO("[Orthogonal %s] adding client behavior: %s", this->getName().c_str(), clBehavior->getName().c_str());
18 clBehavior->stateMachine_ = this->getStateMachine();
19 clBehavior->currentOrthogonal = this;
20
21 clientBehaviors_.back().push_back(clBehavior);
22 }
23 else
24 {
25 ROS_INFO("[orthogonal %s] no client behaviors in this state", this->getName().c_str());
26 }
27 }
virtual std::string getName() const
Definition: orthogonal.cpp:39
std::vector< std::vector< std::shared_ptr< smacc::ISmaccClientBehavior > > > clientBehaviors_
ISmaccStateMachine * getStateMachine()

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

Here is the call graph for this function:

◆ assignClientToOrthogonal()

template<typename TOrthogonal , typename TClient >
void smacc::ISmaccOrthogonal::assignClientToOrthogonal ( TClient client)
protected

Definition at line 59 of file smacc_orthogonal_impl.h.

60{
61 client->setStateMachine(getStateMachine());
62 client->setOrthogonal(this);
63
64 client->template onOrthogonalAllocation<TOrthogonal, TClient>();
65}

References getStateMachine().

Here is the call graph for this function:

◆ getClientBehavior()

template<typename TClientBehavior >
TClientBehavior * smacc::ISmaccOrthogonal::getClientBehavior

Definition at line 68 of file smacc_orthogonal_impl.h.

69{
70 for (auto &cb : this->clientBehaviors_.back())
71 {
72 auto *ret = dynamic_cast<TClientBehavior *>(cb.get());
73 if (ret != nullptr)
74 {
75 return ret;
76 }
77 }
78
79 return nullptr;
80}

References clientBehaviors_.

◆ getClientBehaviors()

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

Definition at line 87 of file smacc_orthogonal_impl.h.

88{
89 return this->clientBehaviors_;
90}

References clientBehaviors_.

◆ getClients()

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

Definition at line 82 of file smacc_orthogonal_impl.h.

83{
84 return clients_;
85}
std::vector< std::shared_ptr< smacc::ISmaccClient > > clients_

References clients_.

◆ getGlobalSMData()

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

Definition at line 99 of file smacc_orthogonal_impl.h.

100{
101 return this->getStateMachine()->getGlobalSMData(name, ret);
102}
bool getGlobalSMData(std::string name, T &ret)

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

Here is the call graph for this function:

◆ getName()

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

Definition at line 39 of file orthogonal.cpp.

40 {
41 return demangleSymbol(typeid(*this).name());
42 }
std::string demangleSymbol()
Definition: introspection.h:75

References smacc::introspection::demangleSymbol().

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

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

◆ getStateMachine()

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

Definition at line 105 of file smacc_orthogonal_impl.h.

105{ return this->stateMachine_; }
ISmaccStateMachine * stateMachine_

References stateMachine_.

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

Here is the caller graph for this function:

◆ initState()

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

Definition at line 33 of file orthogonal.cpp.

34 {
35 ROS_INFO("[Orthogonal %s] initState: %s", this->getName().c_str(), state->getClassName().c_str());
36 clientBehaviors_.push_back(std::vector<std::shared_ptr<smacc::ISmaccClientBehavior>>());
37 }

References clientBehaviors_, smacc::ISmaccState::getClassName(), and getName().

Here is the call graph for this function:

◆ onDispose()

void smacc::ISmaccOrthogonal::onDispose ( )

Definition at line 103 of file orthogonal.cpp.

104 {
105 for (auto &clBehavior : clientBehaviors_.back())
106 {
107 clBehavior->dispose();
108 this->getStateMachine()->disconnectSmaccSignalObject((void*)clBehavior.get());
109 }
110
111 clientBehaviors_.back().clear();
112 clientBehaviors_.pop_back();
113 }
void disconnectSmaccSignalObject(void *object)

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

Here is the call graph for this function:

◆ onEntry()

void smacc::ISmaccOrthogonal::onEntry ( )

Definition at line 55 of file orthogonal.cpp.

56 {
57 if (clientBehaviors_.back().size() > 0)
58 {
59 for (auto &clBehavior : clientBehaviors_.back())
60 {
61 ROS_INFO("[Orthogonal %s] OnEntry, current Behavior: %s", this->getName().c_str(), clBehavior->getName().c_str());
62
63 try
64 {
65 clBehavior->executeOnEntry();
66 }
67 catch (const std::exception &e)
68 {
69 ROS_ERROR("[ClientBehavior %s] Exception on Entry - continuing with next client behavior. Exception info: %s",
70 clBehavior->getName().c_str(), e.what());
71 }
72 }
73 }
74 else
75 {
76 ROS_INFO("[Orthogonal %s] OnEntry", this->getName().c_str());
77 }
78 }

References clientBehaviors_, and getName().

Here is the call graph for this function:

◆ onExit()

void smacc::ISmaccOrthogonal::onExit ( )

Definition at line 80 of file orthogonal.cpp.

81 {
82 if (clientBehaviors_.back().size() > 0)
83 {
84 for (auto &clBehavior : clientBehaviors_.back())
85 {
86 ROS_INFO("[Orthogonal %s] OnExit, current Behavior: %s", this->getName().c_str(), clBehavior->getName().c_str());
87 try
88 {
89 clBehavior->executeOnExit();
90 }
91 catch (const std::exception &e)
92 {
93 ROS_ERROR("[ClientBehavior %s] Exception onExit - continuing with next client behavior. Exception info: %s", clBehavior->getName().c_str(), e.what());
94 }
95 }
96 }
97 else
98 {
99 ROS_INFO("[Orthogonal %s] OnExit", this->getName().c_str());
100 }
101 }

References clientBehaviors_, and getName().

Here is the call graph for this function:

◆ onInitialize()

void smacc::ISmaccOrthogonal::onInitialize ( )
protectedvirtual

Definition at line 29 of file orthogonal.cpp.

30 {
31 }

Referenced by setStateMachine().

Here is the caller graph for this function:

◆ requiresClient()

template<typename SmaccClientType >
bool smacc::ISmaccOrthogonal::requiresClient ( SmaccClientType *&  storage)

Definition at line 16 of file smacc_orthogonal_impl.h.

17{
18 for (auto &client : clients_)
19 {
20 storage = dynamic_cast<SmaccClientType *>(client.get());
21 if (storage != nullptr)
22 return true;
23 }
24
25 auto requiredClientName = demangledTypeName<SmaccClientType>();
26 ROS_WARN_STREAM("Required client ["<< requiredClientName<< "] not found in current orthogonal. Searching in other orthogonals.");
27
28 for (auto &orthoentry : this->getStateMachine()->getOrthogonals())
29 {
30 for (auto &client : orthoentry.second->getClients())
31 {
32 storage = dynamic_cast<SmaccClientType *>(client.get());
33 if (storage != nullptr)
34 {
35 ROS_WARN_STREAM("Required client ["<< requiredClientName<<"] found in other orthogonal.");
36 return true;
37 }
38 }
39 }
40
41 ROS_ERROR_STREAM("Required client ["<< requiredClientName<< "] not found even in other orthogonals. Returning null pointer. If the requested client is used may result in a segmentation fault.");
42 return false;
43}

References clients_, and getStateMachine().

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

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

◆ requiresComponent()

template<typename SmaccComponentType >
void smacc::ISmaccOrthogonal::requiresComponent ( SmaccComponentType *&  storage)

Definition at line 46 of file smacc_orthogonal_impl.h.

47{
48 if (stateMachine_ == nullptr)
49 {
50 ROS_ERROR("Cannot use the requiresComponent funcionality from an orthogonal before onInitialize");
51 }
52 else
53 {
55 }
56}
void requiresComponent(SmaccComponentType *&storage)

References smacc::ISmaccStateMachine::requiresComponent(), and stateMachine_.

Here is the call graph for this function:

◆ runtimeConfigure()

void smacc::ISmaccOrthogonal::runtimeConfigure ( )

Definition at line 44 of file orthogonal.cpp.

45 {
46 for (auto &clBehavior : clientBehaviors_.back())
47 {
48 ROS_INFO("[Orthogonal %s] runtimeConfigure, current Behavior: %s", this->getName().c_str(),
49 clBehavior->getName().c_str());
50
51 clBehavior->runtimeConfigure();
52 }
53 }

References clientBehaviors_, and getName().

Here is the call graph for this function:

◆ setGlobalSMData()

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

Definition at line 93 of file smacc_orthogonal_impl.h.

94{
95 this->getStateMachine()->setGlobalSMData(name, value);
96}
void setGlobalSMData(std::string name, T value)

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

Here is the call graph for this function:

◆ setStateMachine()

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

Definition at line 7 of file orthogonal.cpp.

8 {
9 this->stateMachine_ = value;
10 this->onInitialize();
11 }
virtual void onInitialize()
Definition: orthogonal.cpp:29

References onInitialize(), and stateMachine_.

Here is the call graph for this function:

Friends And Related Function Documentation

◆ ISmaccStateMachine

friend class ISmaccStateMachine
friend

Definition at line 65 of file smacc_orthogonal.h.

Member Data Documentation

◆ clientBehaviors_

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

◆ clients_

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

◆ stateMachine_

ISmaccStateMachine* smacc::ISmaccOrthogonal::stateMachine_
private

Definition at line 62 of file smacc_orthogonal.h.

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


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