SMACC2
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 addClientBehavior (std::shared_ptr< smacc2::ISmaccClientBehavior > clientBehavior)
 
void runtimeConfigure ()
 
void onEntry ()
 
void onExit ()
 
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::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 >
TClientBehavior * getClientBehavior ()
 
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::shared_ptr< smacc2::ISmaccClientBehavior > > clientBehaviors_
 

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 if (clBehavior != nullptr)
52 {
53 RCLCPP_INFO(
54 getLogger(), "[Orthogonal %s] adding client behavior: %s", this->getName().c_str(),
55 clBehavior->getName().c_str());
56 clBehavior->stateMachine_ = this->getStateMachine();
57 clBehavior->currentOrthogonal = this;
58
59 clientBehaviors_.push_back(clBehavior);
60 }
61 else
62 {
63 RCLCPP_INFO(
64 getLogger(), "[orthogonal %s] no client behaviors in this state", this->getName().c_str());
65 }
66}
std::vector< std::shared_ptr< smacc2::ISmaccClientBehavior > > clientBehaviors_
ISmaccStateMachine * getStateMachine()
virtual std::string getName() const
Definition: orthogonal.cpp:70

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

Here is the call graph for this function:

◆ assignClientToOrthogonal()

template<typename TOrthogonal , typename TClient >
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()

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

Definition at line 91 of file smacc_orthogonal_impl.hpp.

92{
93 for (auto & cb : this->clientBehaviors_)
94 {
95 auto * ret = dynamic_cast<TClientBehavior *>(cb.get());
96 if (ret != nullptr)
97 {
98 return ret;
99 }
100 }
101
102 return nullptr;
103}

References clientBehaviors_.

◆ getClientBehaviors()

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

Definition at line 111 of file smacc_orthogonal_impl.hpp.

112{
113 return this->clientBehaviors_;
114}

References clientBehaviors_.

◆ getClients()

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

Definition at line 105 of file smacc_orthogonal_impl.hpp.

106{
107 return clients_;
108}
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 123 of file smacc_orthogonal_impl.hpp.

124{
125 return this->getStateMachine()->getGlobalSMData(name, ret);
126}
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

◆ getName()

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

Definition at line 70 of file orthogonal.cpp.

70{ return demangleSymbol(typeid(*this).name()); }
std::string demangleSymbol(const std::string &name)

References smacc2::introspection::demangleSymbol().

Referenced by addClientBehavior(), 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 ( )

◆ getStateMachine()

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

Definition at line 129 of file smacc_orthogonal_impl.hpp.

129{ return this->stateMachine_; }

References stateMachine_.

Referenced by addClientBehavior(), assignClientToOrthogonal(), getGlobalSMData(), 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:

◆ onEntry()

void smacc2::ISmaccOrthogonal::onEntry ( )

Definition at line 84 of file orthogonal.cpp.

85{
86 if (clientBehaviors_.size() > 0)
87 {
88 for (auto & clBehavior : clientBehaviors_)
89 {
90 RCLCPP_INFO(
91 getLogger(), "[Orthogonal %s] OnEntry, current Behavior: %s", orthogonalName, cbName);
92
93 try
94 {
96 clBehavior->executeOnEntry();
97 }
98 catch (const std::exception & e)
99 {
100 RCLCPP_ERROR(
101 getLogger(),
102 "[ClientBehavior %s] Exception on Entry - continuing with next client behavior. "
103 "Exception info: "
104 "%s",
105 cbName, e.what());
106 }
108 }
109 }
110 else
111 {
112 RCLCPP_INFO(
113 getLogger(), "[Orthogonal %s] OnEntry -> empty orthogonal (no client behavior) ",
115 }
116}
#define orthogonalName
Definition: orthogonal.cpp:27
#define statename
Definition: orthogonal.cpp:26
#define cbName
Definition: orthogonal.cpp:28
void TRACEPOINT(spinOnce)
smacc2_client_behavior_on_entry_start
smacc2_client_behavior_on_entry_end

References cbName, clientBehaviors_, getLogger(), 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 118 of file orthogonal.cpp.

119{
120 if (clientBehaviors_.size() > 0)
121 {
122 for (auto & clBehavior : clientBehaviors_)
123 {
124 RCLCPP_INFO(
125 getLogger(), "[Orthogonal %s] OnExit, current Behavior: %s", orthogonalName, cbName);
126 try
127 {
129 clBehavior->executeOnExit();
130 }
131 catch (const std::exception & e)
132 {
133 RCLCPP_ERROR(
134 getLogger(),
135 "[ClientBehavior %s] Exception onExit - continuing with next client behavior. Exception "
136 "info: %s",
137 cbName, e.what());
138 }
140 }
141
142 int i = 0;
143 for (auto & clBehavior : clientBehaviors_)
144 {
145 clBehavior->dispose();
146 clientBehaviors_[i] = nullptr;
147 }
148
149 clientBehaviors_.clear();
150 }
151 else
152 {
153 RCLCPP_INFO(getLogger(), "[Orthogonal %s] OnExit", orthogonalName);
154 }
155}
smacc2_client_behavior_on_exit_end
smacc2_client_behavior_on_exit_start

References cbName, clientBehaviors_, getLogger(), 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

Reimplemented in sm_atomic_subscribers_performance_test::OrSubscriber, $sm_name$::OrTimer, sm_advanced_recovery_1::OrKeyboard, sm_advanced_recovery_1::OrSubscriber, sm_advanced_recovery_1::OrTimer, sm_advanced_recovery_1::OrUpdatablePublisher, sm_atomic::OrTimer, sm_atomic_24hr::OrTimer, sm_autoware_avp::OrAutowareAuto, sm_autoware_avp::OrTimer, sm_aws_warehouse_navigation::OrNavigation, sm_branching::OrTimer, sm_dance_bot::OrLED, sm_dance_bot::OrNavigation, sm_dance_bot::OrObstaclePerception, sm_dance_bot::OrService3, sm_dance_bot::OrStringPublisher, sm_dance_bot::OrTemperatureSensor, sm_dance_bot::OrTimer, sm_dance_bot::OrUpdatablePublisher, sm_dance_bot_strikes_back::OrLED, sm_dance_bot_strikes_back::OrNavigation, sm_dance_bot_strikes_back::OrObstaclePerception, sm_dance_bot_strikes_back::OrService3, sm_dance_bot_strikes_back::OrStringPublisher, sm_dance_bot_strikes_back::OrTemperatureSensor, sm_dance_bot_strikes_back::OrTimer, sm_dance_bot_strikes_back::OrUpdatablePublisher, sm_dance_bot_warehouse::OrLED, sm_dance_bot_warehouse::OrNavigation, sm_dance_bot_warehouse::OrObstaclePerception, sm_dance_bot_warehouse::OrService3, sm_dance_bot_warehouse::OrStringPublisher, sm_dance_bot_warehouse::OrTemperatureSensor, sm_dance_bot_warehouse::OrTimer, sm_dance_bot_warehouse::OrUpdatablePublisher, sm_dance_bot_warehouse_2::OrLED, sm_dance_bot_warehouse_2::OrNavigation, sm_dance_bot_warehouse_2::OrObstaclePerception, sm_dance_bot_warehouse_2::OrService3, sm_dance_bot_warehouse_2::OrStringPublisher, sm_dance_bot_warehouse_2::OrTemperatureSensor, sm_dance_bot_warehouse_2::OrTimer, sm_dance_bot_warehouse_2::OrUpdatablePublisher, sm_dance_bot_warehouse_3::OrLED, sm_dance_bot_warehouse_3::OrNavigation, sm_dance_bot_warehouse_3::OrObstaclePerception, sm_dance_bot_warehouse_3::OrService3, sm_dance_bot_warehouse_3::OrStringPublisher, sm_dance_bot_warehouse_3::OrTemperatureSensor, sm_dance_bot_warehouse_3::OrTimer, sm_dance_bot_warehouse_3::OrUpdatablePublisher, sm_ferrari::OrKeyboard, sm_ferrari::OrSubscriber, sm_ferrari::OrTimer, sm_ferrari::OrUpdatablePublisher, sm_husky_barrel_search_1::OrLedArray, sm_husky_barrel_search_1::OrNavigation, sm_husky_barrel_search_1::OrPerception, sm_multi_stage_1::OrKeyboard, sm_multi_stage_1::OrSubscriber, sm_multi_stage_1::OrTimer, sm_multi_stage_1::OrUpdatablePublisher, sm_pubsub_1::OrKeyboard, sm_pubsub_1::OrSubscriber, sm_pubsub_1::OrTimer, sm_pubsub_1::OrUpdatablePublisher, sm_respira_1::OrKeyboard, sm_respira_1::OrSubscriber, sm_respira_1::OrTimer, sm_respira_1::OrUpdatablePublisher, sm_test_moveit_ur5_sim::OrArm, sm_three_some::OrKeyboard, sm_three_some::OrSubscriber, sm_three_some::OrTimer, and sm_three_some::OrUpdatablePublisher.

Definition at line 68 of file orthogonal.cpp.

68{}

Referenced by setStateMachine().

Here is the caller graph for this function:

◆ requiresClient()

template<typename SmaccClientType >
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}

References clients_, getLogger(), 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()

template<typename SmaccComponentType >
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)

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

Here is the call graph for this function:

◆ runtimeConfigure()

void smacc2::ISmaccOrthogonal::runtimeConfigure ( )

Definition at line 72 of file orthogonal.cpp.

73{
74 for (auto & clBehavior : clientBehaviors_)
75 {
76 RCLCPP_INFO(
77 getLogger(), "[Orthogonal %s] runtimeConfigure, current Behavior: %s",
78 this->getName().c_str(), clBehavior->getName().c_str());
79
80 clBehavior->runtimeConfigure();
81 }
82}

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

Here is the call graph for this function:

◆ setGlobalSMData()

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

Definition at line 117 of file smacc_orthogonal_impl.hpp.

118{
119 this->getStateMachine()->setGlobalSMData(name, value);
120}
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()
Definition: orthogonal.cpp:68

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

Here is the call graph for this function:

Friends And Related Function Documentation

◆ ISmaccStateMachine

friend class ISmaccStateMachine
friend

Definition at line 81 of file smacc_orthogonal.hpp.

Member Data Documentation

◆ clientBehaviors_

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

◆ clients_

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

◆ stateMachine_

ISmaccStateMachine* smacc2::ISmaccOrthogonal::stateMachine_
private

Definition at line 78 of file smacc_orthogonal.hpp.

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


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