22#include <lifecycle_msgs/msg/transition_event.hpp>
23#include <lifecycle_msgs/srv/change_state.hpp>
24#include <lifecycle_msgs/srv/get_state.hpp>
30template <
typename TSourceObject,
typename TOrthogonal>
32:
sc::event<EvLifecycleNodeChangeState<TSourceObject, TOrthogonal>>
37template <
typename TSourceObject,
typename TOrthogonal>
42template <
typename TSourceObject,
typename TOrthogonal>
47template <
typename TSourceObject,
typename TOrthogonal>
52template <
typename TSourceObject,
typename TOrthogonal>
57template <
typename TSourceObject,
typename TOrthogonal>
62template <
typename TSourceObject,
typename TOrthogonal>
64:
sc::event<EvTransitionUnconfiguredShutdown<TSourceObject, TOrthogonal>>
68template <
typename TSourceObject,
typename TOrthogonal>
70:
sc::event<EvTransitionInactiveShutdown<TSourceObject, TOrthogonal>>
74template <
typename TSourceObject,
typename TOrthogonal>
76:
sc::event<EvTransitionActiveShutdown<TSourceObject, TOrthogonal>>
80template <
typename TSourceObject,
typename TOrthogonal>
85template <
typename TSourceObject,
typename TOrthogonal>
87:
sc::event<EvTransitionOnConfigureSuccess<TSourceObject, TOrthogonal>>
91template <
typename TSourceObject,
typename TOrthogonal>
93:
sc::event<EvTransitionOnConfigureFailure<TSourceObject, TOrthogonal>>
97template <
typename TSourceObject,
typename TOrthogonal>
99:
sc::event<EvTransitionOnConfigureError<TSourceObject, TOrthogonal>>
103template <
typename TSourceObject,
typename TOrthogonal>
105:
sc::event<EvTransitionOnActivateSuccess<TSourceObject, TOrthogonal>>
109template <
typename TSourceObject,
typename TOrthogonal>
111:
sc::event<EvTransitionOnActivateFailure<TSourceObject, TOrthogonal>>
115template <
typename TSourceObject,
typename TOrthogonal>
117:
sc::event<EvTransitionOnActivateError<TSourceObject, TOrthogonal>>
121template <
typename TSourceObject,
typename TOrthogonal>
123:
sc::event<EvTransitionOnDeactivateSuccess<TSourceObject, TOrthogonal>>
127template <
typename TSourceObject,
typename TOrthogonal>
129:
sc::event<EvTransitionOnDeactivateFailure<TSourceObject, TOrthogonal>>
133template <
typename TSourceObject,
typename TOrthogonal>
135:
sc::event<EvTransitionOnDeactivateError<TSourceObject, TOrthogonal>>
139template <
typename TSourceObject,
typename TOrthogonal>
141:
sc::event<EvTransitionOnCleanupSuccess<TSourceObject, TOrthogonal>>
145template <
typename TSourceObject,
typename TOrthogonal>
147:
sc::event<EvTransitionOnCleanupFailure<TSourceObject, TOrthogonal>>
151template <
typename TSourceObject,
typename TOrthogonal>
153:
sc::event<EvTransitionOnCleanupError<TSourceObject, TOrthogonal>>
157template <
typename TSourceObject,
typename TOrthogonal>
159:
sc::event<EvTransitionOnShutdownSuccess<TSourceObject, TOrthogonal>>
163template <
typename TSourceObject,
typename TOrthogonal>
165:
sc::event<EvTransitionOnShutdownFailure<TSourceObject, TOrthogonal>>
169template <
typename TSourceObject,
typename TOrthogonal>
171:
sc::event<EvTransitionOnShutdownError<TSourceObject, TOrthogonal>>
175template <
typename TSourceObject,
typename TOrthogonal>
177:
sc::event<EvTransitionOnErrorSuccess<TSourceObject, TOrthogonal>>
181template <
typename TSourceObject,
typename TOrthogonal>
183:
sc::event<EvTransitionOnErrorFailure<TSourceObject, TOrthogonal>>
187template <
typename TSourceObject,
typename TOrthogonal>
223 virtual void onTransitionEvent(
const lifecycle_msgs::msg::TransitionEvent::SharedPtr msg);
225 boost::signals2::signal<void(
const lifecycle_msgs::msg::TransitionEvent::SharedPtr)>
268 template <
typename TOrthogonal,
typename TSourceObject>
273 RCLCPP_INFO(this->
getLogger(),
"postOnTransitionCreate_");
283 this->postEvent<EvTransitionConfigure<TSourceObject, TOrthogonal>>();
289 this->postEvent<EvTransitionActivate<TSourceObject, TOrthogonal>>();
295 this->postEvent<EvTransitionDeactivate<TSourceObject, TOrthogonal>>();
301 this->postEvent<EvTransitionUnconfiguredShutdown<TSourceObject, TOrthogonal>>();
307 this->postEvent<EvTransitionInactiveShutdown<TSourceObject, TOrthogonal>>();
313 this->postEvent<EvTransitionActiveShutdown<TSourceObject, TOrthogonal>>();
319 this->postEvent<EvTransitionDestroy<TSourceObject, TOrthogonal>>();
325 this->postEvent<EvTransitionOnConfigureSuccess<TSourceObject, TOrthogonal>>();
331 this->postEvent<EvTransitionOnConfigureFailure<TSourceObject, TOrthogonal>>();
337 this->postEvent<EvTransitionOnConfigureError<TSourceObject, TOrthogonal>>();
343 this->postEvent<EvTransitionOnActivateSuccess<TSourceObject, TOrthogonal>>();
349 this->postEvent<EvTransitionOnActivateFailure<TSourceObject, TOrthogonal>>();
355 this->postEvent<EvTransitionOnActivateError<TSourceObject, TOrthogonal>>();
361 this->postEvent<EvTransitionOnDeactivateSuccess<TSourceObject, TOrthogonal>>();
367 this->postEvent<EvTransitionOnDeactivateFailure<TSourceObject, TOrthogonal>>();
373 this->postEvent<EvTransitionOnDeactivateError<TSourceObject, TOrthogonal>>();
379 this->postEvent<EvTransitionCleanup<TSourceObject, TOrthogonal>>();
385 this->postEvent<EvTransitionOnCleanupSuccess<TSourceObject, TOrthogonal>>();
391 this->postEvent<EvTransitionOnCleanupFailure<TSourceObject, TOrthogonal>>();
397 this->postEvent<EvTransitionOnCleanupError<TSourceObject, TOrthogonal>>();
403 this->postEvent<EvTransitionOnShutdownSuccess<TSourceObject, TOrthogonal>>();
409 this->postEvent<EvTransitionOnShutdownFailure<TSourceObject, TOrthogonal>>();
415 this->postEvent<EvTransitionOnShutdownError<TSourceObject, TOrthogonal>>();
421 this->postEvent<EvTransitionOnErrorSuccess<TSourceObject, TOrthogonal>>();
427 this->postEvent<EvTransitionOnErrorFailure<TSourceObject, TOrthogonal>>();
433 this->postEvent<EvTransitionOnErrorError<TSourceObject, TOrthogonal>>();
441 rclcpp::Subscription<lifecycle_msgs::msg::TransitionEvent>::SharedPtr
std::function< void()> postOnTransitionActivate_
virtual void onTransitionEvent(const lifecycle_msgs::msg::TransitionEvent::SharedPtr msg)
boost::signals2::signal< void()> onTransitionOnShutdownSuccess_
std::function< void()> postOnTransitionOnConfigureFailure_
boost::signals2::signal< void()> onTransitionOnErrorSuccess_
std::function< void()> postOnTransitionOnDeactivateFailure_
boost::signals2::signal< void()> onTransitionInactiveShutdown_
boost::signals2::signal< void()> onTransitionOnActiveShutdownSuccess_
boost::signals2::signal< void()> onTransitionDeactivate_
boost::signals2::signal< void()> onTransitionUnconfiguredShutdown_
boost::signals2::signal< void()> onTransitionCreate_
boost::signals2::signal< void()> onTransitionOnDeactivateFailure_
boost::signals2::signal< void()> onTransitionOnShutdownError_
boost::signals2::signal< void()> onTransitionOnActivateSuccess_
boost::signals2::signal< void()> onTransitionOnDeactivateSuccess_
std::function< void()> postOnTransitionOnCleanupFailure_
boost::signals2::signal< void()> onTransitionActivate_
virtual ~ClLifecycleNode()
boost::signals2::signal< void()> onTransitionOnActivateError_
const std::string node_change_state_topic
std::function< void()> postOnTransitionConfigure_
boost::signals2::signal< void()> onTransitionOnConfigureFailure_
boost::signals2::signal< void()> onTransitionOnErrorFailure_
std::function< void()> postOnTransitionUnconfiguredShutdown_
boost::signals2::signal< void()> onTransitionOnActiveShutdownError_
void changeState(uint8_t state)
rclcpp::Client< lifecycle_msgs::srv::GetState >::SharedPtr client_get_state_
boost::signals2::signal< void()> onTransitionOnConfigureSuccess_
std::function< void()> postOnTransitionOnConfigureSuccess_
boost::signals2::signal< void()> onTransitionActiveShutdown_
rclcpp::Subscription< lifecycle_msgs::msg::TransitionEvent >::SharedPtr subscription_transition_event_
boost::signals2::signal< void()> onTransitionOnErrorError_
const std::string node_transition_event_topic
std::function< void()> postOnTransitionOnErrorError_
void onOrthogonalAllocation()
lifecycle_msgs::msg::TransitionEvent::SharedPtr lastTransitionEvent_
rclcpp::Client< lifecycle_msgs::srv::ChangeState >::SharedPtr client_change_state_
boost::signals2::signal< void()> onTransitionDestroy_
boost::signals2::signal< void(const lifecycle_msgs::msg::TransitionEvent::SharedPtr)> onTransitionEventSignal
std::function< void()> postOnTransitionOnErrorSuccess_
std::function< void()> postOnTransitionOnCleanupSuccess_
boost::signals2::signal< void()> onTransitionCleanup_
std::function< void()> postOnTransitionOnCleanupError_
std::function< void()> postOnTransitionInactiveShutdown_
void onInitialize() override
boost::signals2::signal< void()> onTransitionOnActiveShutdownFailure_
std::function< void()> postOnTransitionCleanup_
std::function< void()> postOnTransitionOnShutdownError_
std::function< void()> postOnTransitionOnErrorFailure_
std::function< void()> postOnTransitionOnDeactivateSuccess_
std::function< void()> postOnTransitionDeactivate_
std::function< void()> postOnTransitionOnShutdownFailure_
const std::string node_get_state_topic
std::function< void()> postOnTransitionOnConfigureError_
boost::signals2::signal< void()> onTransitionOnConfigureError_
boost::signals2::signal< void()> onTransitionOnActivateFailure_
std::function< void()> postOnTransitionOnActivateFailure_
std::function< void()> postOnTransitionOnShutdownSuccess_
boost::signals2::signal< void()> onTransitionOnCleanupSuccess_
boost::signals2::signal< void()> onTransitionOnDeactivateError_
std::function< void()> postOnTransitionDestroy_
boost::signals2::signal< void()> onTransitionOnShutdownFailure_
boost::signals2::signal< void()> onTransitionOnCleanupFailure_
std::function< void()> postOnTransitionCreate_
std::function< void()> postOnTransitionActiveShutdown_
boost::signals2::signal< void()> onTransitionConfigure_
std::function< void()> postOnTransitionOnActivateSuccess_
boost::signals2::signal< void()> onTransitionOnCleanupError_
std::function< void()> postOnTransitionOnDeactivateError_
std::function< void()> postOnTransitionOnActivateError_
rclcpp::Logger getLogger()